diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 4078cd970e4879cda5150bf0fb2e8d30231597e5..9c760226064c744345c5a744757ffc9f52c6dacd 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -10,7 +10,7 @@ MESSAGE(STATUS ${CMAKE_MODULE_PATH})
 
 # Some wolf compilation options
 
-IF((CMAKE_BUILD_TYPE MATCHES DEBUG) OR (CMAKE_BUILD_TYPE MATCHES debug))
+IF((CMAKE_BUILD_TYPE MATCHES DEBUG) OR (CMAKE_BUILD_TYPE MATCHES debug) OR (CMAKE_BUILD_TYPE MATCHES Debug))
   set(_WOLF_DEBUG true)
 ENDIF()
 
@@ -155,8 +155,9 @@ ENDIF(YAMLCPP_FOUND)
 SET(HDRS_BASE
     capture_base.h
     constraint_analytic.h
-    constraint_base.h
     constraint_autodiff.h
+    constraint_base.h
+    factory.h
     feature_base.h
     feature_match.h
     frame_base.h
@@ -198,10 +199,11 @@ SET(HDRS
     capture_void.h
     constraint_container.h
     constraint_corner_2D.h
-    #constraint_epipolar.h
     constraint_AHP.h
+    constraint_epipolar.h
     constraint_imu.h
     constraint_fix.h
+    constraint_fix_bias.h
     constraint_fix_3D.h
     constraint_gps_2D.h
     constraint_gps_pseudorange_3D.h
@@ -369,9 +371,10 @@ IF (OpenCV_FOUND)
     SET(HDRS ${HDRS}
         active_search.h
         capture_image.h
+        constraint_AHP.h
         feature_point_image.h
         landmark_AHP.h
-    	landmark_point_3d.h
+        landmark_point_3d.h
         processor_image_feature.h
         processor_image_landmark.h
         )
@@ -380,7 +383,7 @@ IF (OpenCV_FOUND)
         capture_image.cpp
         feature_point_image.cpp
         landmark_AHP.cpp
-    	landmark_point_3d.cpp
+        landmark_point_3d.cpp
         processor_image_feature.cpp
         processor_image_landmark.cpp
         )
@@ -396,14 +399,14 @@ IF(YAMLCPP_FOUND)
     SET(HDRS ${HDRS}
         yaml/yaml_conversion.h
         )
-        
-    
 
     # sources
     SET(SRCS ${SRCS}
         yaml/processor_odom_3D_yaml.cpp
+        yaml/processor_imu_yaml.cpp
         yaml/sensor_camera_yaml.cpp
         yaml/sensor_odom_3D_yaml.cpp
+        yaml/sensor_imu_yaml.cpp
         )
     IF(laser_scan_utils_FOUND)
         SET(SRCS ${SRCS}
diff --git a/src/capture_imu.cpp b/src/capture_imu.cpp
index b51480ee5ac37d30d601443468fd39d0bdc8f8d1..6b405c95b478163bb10d7204e824478f1ecf3011 100644
--- a/src/capture_imu.cpp
+++ b/src/capture_imu.cpp
@@ -1,16 +1,40 @@
 #include "capture_imu.h"
+#include "sensor_imu.h"
 
 namespace wolf {
 
 
-CaptureIMU::CaptureIMU(const TimeStamp& _init_ts, SensorBasePtr _sensor_ptr,
-                             const Eigen::Vector6s& _acc_gyro_data) :
-        CaptureMotion(_init_ts, _sensor_ptr, _acc_gyro_data, 10, 9 )
+CaptureIMU::CaptureIMU(const TimeStamp& _init_ts, SensorBasePtr _sensor_ptr, const Eigen::Vector6s& _acc_gyro_data, 
+                        FrameBasePtr _origin_frame_ptr) :
+        CaptureMotion(_init_ts, _sensor_ptr, _acc_gyro_data, 6, 10, 9, 6, _origin_frame_ptr)
 {
     setType("IMU");
+
+    SensorIMUPtr imu_ptr = std::static_pointer_cast<SensorIMU>(_sensor_ptr);
+
+    Scalar acc_var  = imu_ptr->getAccelNoise() * imu_ptr->getAccelNoise();
+    Scalar gyro_var = imu_ptr->getGyroNoise()  * imu_ptr->getGyroNoise();
+
+    Vector6s data_vars; data_vars << acc_var, acc_var, acc_var, gyro_var, gyro_var, gyro_var;
+
+    Matrix6s data_cov; data_cov.setZero();
+
+    data_cov.diagonal() = data_vars;
+
+    setDataCovariance(data_cov);
+
 //    std::cout << "constructed    +C-IMU" << id() << std::endl;
 }
 
+CaptureIMU::CaptureIMU(const TimeStamp& _init_ts, SensorBasePtr _sensor_ptr, const Eigen::Vector6s& _acc_gyro_data, 
+                       const Eigen::MatrixXs& _data_cov, FrameBasePtr _origin_frame_ptr) :
+        CaptureMotion(_init_ts, _sensor_ptr, _acc_gyro_data, _data_cov, 6, 10, 9, 6, _origin_frame_ptr)
+{
+    setType("IMU");
+//    std::cout << "constructed    +C-IMU" << id() << std::endl;
+}
+
+
 CaptureIMU::~CaptureIMU()
 {
 //    std::cout << "destructed     -C-IMU" << id() << std::endl;
diff --git a/src/capture_imu.h b/src/capture_imu.h
index 55e8d88489c58ccadbea6dcfa1da361279de9901..f38b171bbc34380934a943879fa5c775e225b412 100644
--- a/src/capture_imu.h
+++ b/src/capture_imu.h
@@ -12,7 +12,12 @@ class CaptureIMU : public CaptureMotion
 {
     public:
 
-        CaptureIMU(const TimeStamp& _init_ts, SensorBasePtr _sensor_ptr, const Eigen::Vector6s& _data);
+        CaptureIMU(const TimeStamp& _init_ts, SensorBasePtr _sensor_ptr, const Eigen::Vector6s& _data, 
+                    FrameBasePtr _origin_frame_ptr = nullptr);
+
+        CaptureIMU(const TimeStamp& _init_ts, SensorBasePtr _sensor_ptr, const Eigen::Vector6s& _data, 
+                   const Eigen::MatrixXs& _data_cov, FrameBasePtr _origin_frame_ptr = nullptr);
+
         virtual ~CaptureIMU();
 
 };
diff --git a/src/capture_motion.h b/src/capture_motion.h
index da57f463f79affdcfc72e8abf4fd0e27eb097fce..131890005da3384547367460e4bebe558cec19bf 100644
--- a/src/capture_motion.h
+++ b/src/capture_motion.h
@@ -48,15 +48,12 @@ class CaptureMotion : public CaptureBase
     public:
         CaptureMotion(const TimeStamp& _ts, SensorBasePtr _sensor_ptr,
                       const Eigen::VectorXs& _data,
-                      Size _delta_size, Size _delta_cov_size,
+                      Size _data_size, Size _delta_size, Size _cov_size, Size _calib_size,
                       FrameBasePtr _origin_frame_ptr = nullptr);
 
-//        CaptureMotion(const TimeStamp& _ts, SensorBasePtr _sensor_ptr, const Eigen::VectorXs& _data,
-//                      const Eigen::VectorXs& _data_sigmas, FrameBasePtr _origin_frame_ptr = nullptr);
-
         CaptureMotion(const TimeStamp& _ts, SensorBasePtr _sensor_ptr,
                       const Eigen::VectorXs& _data, const Eigen::MatrixXs& _data_cov,
-                      Size _delta_size, Size _delta_cov_size,
+                      Size _data_size, Size _delta_size, Size _cov_size, Size _calib_size,
                       FrameBasePtr _origin_frame_ptr = nullptr);
 
         virtual ~CaptureMotion();
@@ -81,27 +78,30 @@ class CaptureMotion : public CaptureBase
         FrameBasePtr origin_frame_ptr_; ///< Pointer to the origin frame of the motion
 };
 
-inline CaptureMotion::CaptureMotion(const TimeStamp& _ts, SensorBasePtr _sensor_ptr,
+inline CaptureMotion::CaptureMotion(const TimeStamp& _ts,
+                                    SensorBasePtr _sensor_ptr,
                                     const Eigen::VectorXs& _data,
-                                    Size _delta_size, Size _delta_cov_size,
+                                    Size _data_size, Size _delta_size, Size _delta_cov_size, Size _calib_size,
                                     FrameBasePtr _origin_frame_ptr) :
         CaptureBase("MOTION", _ts, _sensor_ptr),
         data_(_data),
-        data_cov_(Eigen::MatrixXs::Identity(_data.rows(), _data.rows())),
-        buffer_(_delta_size,_delta_cov_size),
+        data_cov_(Eigen::MatrixXs::Zero(_data.rows(), _data.rows())), // Someone should test this zero and do something smart accordingly
+        buffer_(_data_size, _delta_size,_delta_cov_size, _calib_size),
         origin_frame_ptr_(_origin_frame_ptr)
 {
     //
 }
 
-inline CaptureMotion::CaptureMotion(const TimeStamp& _ts, SensorBasePtr _sensor_ptr,
-                                    const Eigen::VectorXs& _data, const Eigen::MatrixXs& _data_cov,
-                                    Size _delta_size, Size _delta_cov_size,
+inline CaptureMotion::CaptureMotion(const TimeStamp& _ts,
+                                    SensorBasePtr _sensor_ptr,
+                                    const Eigen::VectorXs& _data,
+                                    const Eigen::MatrixXs& _data_cov,
+                                    Size _data_size, Size _delta_size, Size _delta_cov_size, Size _calib_size,
                                     FrameBasePtr _origin_frame_ptr) :
         CaptureBase("MOTION", _ts, _sensor_ptr),
         data_(_data),
         data_cov_(_data_cov),
-        buffer_(_delta_size,_delta_cov_size),
+        buffer_(_data_size, _delta_size,_delta_cov_size, _calib_size),
         origin_frame_ptr_(_origin_frame_ptr)
 {
     //
diff --git a/src/ceres_wrapper/ceres_manager.cpp b/src/ceres_wrapper/ceres_manager.cpp
index 0ea5290f3134cac1a61c7d88f24aaa8fada04177..acf4585d32b2310294be3da40ea4c236503c4d78 100644
--- a/src/ceres_wrapper/ceres_manager.cpp
+++ b/src/ceres_wrapper/ceres_manager.cpp
@@ -88,7 +88,7 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
         case ALL:
         {
             // first create a vector containing all state blocks
-            std::vector<StateBlockPtr> all_state_blocks, landmark_state_blocks;
+            std::vector<StateBlockPtr> all_state_blocks, landmark_state_blocks, Frame_state_blocks;
             //frame state blocks
             for(auto fr_ptr : wolf_problem_->getTrajectoryPtr()->getFrameList())
                 if (fr_ptr->isKey())
@@ -106,8 +106,8 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
             for (unsigned int i = 0; i < all_state_blocks.size(); i++)
                 for  (unsigned int j = i; j < all_state_blocks.size(); j++)
                 {
-                    state_block_pairs.push_back(std::make_pair(all_state_blocks[i],all_state_blocks[j]));
-                    double_pairs.push_back(std::make_pair(all_state_blocks[i]->getPtr(),all_state_blocks[j]->getPtr()));
+                    state_block_pairs.emplace_back(all_state_blocks[i],all_state_blocks[j]);
+                    double_pairs.emplace_back(all_state_blocks[i]->getPtr(),all_state_blocks[j]->getPtr());
                 }
             break;
         }
@@ -121,10 +121,9 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
                             for(auto sb2 : fr_ptr->getStateBlockVec())
                                 if (sb)
                                 {
-                                    state_block_pairs.push_back(std::make_pair(sb, sb2));
-                                    double_pairs.push_back(std::make_pair(sb->getPtr(), sb2->getPtr()));
-                                    if (sb == sb2)
-                                        break;
+                                    state_block_pairs.emplace_back(sb, sb2);
+                                    double_pairs.emplace_back(sb->getPtr(), sb2->getPtr());
+                                    if (sb == sb2) break;
                                 }
 
             // landmark state blocks
@@ -132,10 +131,21 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
                 for (auto sb : l_ptr->getUsedStateBlockVec())
                     for(auto sb2 : l_ptr->getUsedStateBlockVec())
                     {
-                        state_block_pairs.push_back(std::make_pair(sb, sb2));
-                        double_pairs.push_back(std::make_pair(sb->getPtr(), sb2->getPtr()));
+                        state_block_pairs.emplace_back(sb, sb2);
+                        double_pairs.emplace_back(sb->getPtr(), sb2->getPtr());
                         if (sb == sb2) break;
                     }
+//            // loop all marginals (PO marginals)
+//            for (unsigned int i = 0; 2*i+1 < all_state_blocks.size(); i++)
+//            {
+//                state_block_pairs.emplace_back(all_state_blocks[2*i],all_state_blocks[2*i]);
+//                state_block_pairs.emplace_back(all_state_blocks[2*i],all_state_blocks[2*i+1]);
+//                state_block_pairs.emplace_back(all_state_blocks[2*i+1],all_state_blocks[2*i+1]);
+//
+//                double_pairs.emplace_back(all_state_blocks[2*i]->getPtr(),all_state_blocks[2*i]->getPtr());
+//                double_pairs.emplace_back(all_state_blocks[2*i]->getPtr(),all_state_blocks[2*i+1]->getPtr());
+//                double_pairs.emplace_back(all_state_blocks[2*i+1]->getPtr(),all_state_blocks[2*i+1]->getPtr());
+//            }
             break;
         }
         case ROBOT_LANDMARKS:
@@ -143,13 +153,13 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
             //robot-robot
             auto last_key_frame = wolf_problem_->getLastKeyFramePtr();
 
-            state_block_pairs.push_back(std::make_pair(last_key_frame->getPPtr(), last_key_frame->getPPtr()));
-            state_block_pairs.push_back(std::make_pair(last_key_frame->getPPtr(), last_key_frame->getOPtr()));
-            state_block_pairs.push_back(std::make_pair(last_key_frame->getOPtr(), last_key_frame->getOPtr()));
+            state_block_pairs.emplace_back(last_key_frame->getPPtr(), last_key_frame->getPPtr());
+            state_block_pairs.emplace_back(last_key_frame->getPPtr(), last_key_frame->getOPtr());
+            state_block_pairs.emplace_back(last_key_frame->getOPtr(), last_key_frame->getOPtr());
 
-            double_pairs.push_back(std::make_pair(last_key_frame->getPPtr()->getPtr(), last_key_frame->getPPtr()->getPtr()));
-            double_pairs.push_back(std::make_pair(last_key_frame->getPPtr()->getPtr(), last_key_frame->getOPtr()->getPtr()));
-            double_pairs.push_back(std::make_pair(last_key_frame->getOPtr()->getPtr(), last_key_frame->getOPtr()->getPtr()));
+            double_pairs.emplace_back(last_key_frame->getPPtr()->getPtr(), last_key_frame->getPPtr()->getPtr());
+            double_pairs.emplace_back(last_key_frame->getPPtr()->getPtr(), last_key_frame->getOPtr()->getPtr());
+            double_pairs.emplace_back(last_key_frame->getOPtr()->getPtr(), last_key_frame->getOPtr()->getPtr());
 
             // landmarks
             std::vector<StateBlockPtr> landmark_state_blocks;
@@ -161,16 +171,16 @@ void CeresManager::computeCovariances(CovarianceBlocksToBeComputed _blocks)
                 for (auto state_it = landmark_state_blocks.begin(); state_it != landmark_state_blocks.end(); state_it++)
                 {
                     // robot - landmark
-                    state_block_pairs.push_back(std::make_pair(last_key_frame->getPPtr(), *state_it));
-                    state_block_pairs.push_back(std::make_pair(last_key_frame->getOPtr(), *state_it));
-                    double_pairs.push_back(std::make_pair(last_key_frame->getPPtr()->getPtr(), (*state_it)->getPtr()));
-                    double_pairs.push_back(std::make_pair(last_key_frame->getOPtr()->getPtr(), (*state_it)->getPtr()));
+                    state_block_pairs.emplace_back(last_key_frame->getPPtr(), *state_it);
+                    state_block_pairs.emplace_back(last_key_frame->getOPtr(), *state_it);
+                    double_pairs.emplace_back(last_key_frame->getPPtr()->getPtr(), (*state_it)->getPtr());
+                    double_pairs.emplace_back(last_key_frame->getOPtr()->getPtr(), (*state_it)->getPtr());
 
                     // landmark marginal
                     for (auto next_state_it = state_it; next_state_it != landmark_state_blocks.end(); next_state_it++)
                     {
-                        state_block_pairs.push_back(std::make_pair(*state_it, *next_state_it));
-                        double_pairs.push_back(std::make_pair((*state_it)->getPtr(), (*next_state_it)->getPtr()));
+                        state_block_pairs.emplace_back(*state_it, *next_state_it);
+                        double_pairs.emplace_back((*state_it)->getPtr(), (*next_state_it)->getPtr());
                     }
                 }
             }
@@ -300,7 +310,7 @@ ceres::CostFunctionPtr CeresManager::createCostFunction(ConstraintBasePtr _ctr_p
 	assert(_ctr_ptr != nullptr);
 	//std::cout << "creating cost function for constraint " << _ctr_ptr->id() << std::endl;
 
-    // analitic jacobian
+    // analitic & autodiff jacobian
     if (_ctr_ptr->getJacobianMethod() == JAC_ANALYTIC || _ctr_ptr->getJacobianMethod() == JAC_AUTO)
         return std::make_shared<CostFunctionWrapper>(_ctr_ptr);
 
diff --git a/src/constraint_AHP.h b/src/constraint_AHP.h
index ad5ebeeaa0d9c52f8bae81893efc7faa0275c79f..9af047fad2470d19fce4eb42adfc3d2f66bc1745 100644
--- a/src/constraint_AHP.h
+++ b/src/constraint_AHP.h
@@ -25,12 +25,13 @@ class ConstraintAHP : public ConstraintAutodiff<ConstraintAHP, 2, 3, 4, 3, 4, 4>
 
     public:
 
-        ConstraintAHP(FeatureBasePtr    _ftr_ptr,
-                      LandmarkAHPPtr    _landmark_ptr,
+        ConstraintAHP(const FeatureBasePtr&   _ftr_ptr,
+                      const LandmarkAHPPtr&   _landmark_ptr,
+                      const ProcessorBasePtr& _processor_ptr = nullptr,
                       bool              _apply_loss_function = false,
                       ConstraintStatus  _status = CTR_ACTIVE);
 
-        virtual ~ConstraintAHP();
+        virtual ~ConstraintAHP() = default;
 
         template<typename T>
         void expectation(const T* const _current_frame_p,
@@ -52,25 +53,28 @@ class ConstraintAHP : public ConstraintAutodiff<ConstraintAHP, 2, 3, 4, 3, 4, 4>
 
         /** \brief Returns the jacobians computation method
          **/
-        virtual JacobianMethod getJacobianMethod() const;
+        virtual JacobianMethod getJacobianMethod() const override;
 
 
         // Static creator method
-        static ConstraintAHPPtr create(FeatureBasePtr   _ftr_ptr,
-                                       LandmarkAHPPtr   _lmk_ahp_ptr,
-                                       bool             _apply_loss_function = false,
-                                       ConstraintStatus _status              = CTR_ACTIVE);
+        static ConstraintAHPPtr create(const FeatureBasePtr&   _ftr_ptr,
+                                       const LandmarkAHPPtr&   _lmk_ahp_ptr,
+                                       const ProcessorBasePtr& _processor_ptr = nullptr,
+                                       bool             _apply_loss_function  = false,
+                                       ConstraintStatus _status               = CTR_ACTIVE);
 
 };
 
-inline ConstraintAHP::ConstraintAHP(FeatureBasePtr   _ftr_ptr,
-                                    LandmarkAHPPtr   _landmark_ptr,
+inline ConstraintAHP::ConstraintAHP(const FeatureBasePtr&   _ftr_ptr,
+                                    const LandmarkAHPPtr&   _landmark_ptr,
+                                    const ProcessorBasePtr& _processor_ptr,
                                     bool             _apply_loss_function,
                                     ConstraintStatus _status) :
         ConstraintAutodiff<ConstraintAHP, 2, 3, 4, 3, 4, 4>(CTR_AHP,
                                            _landmark_ptr->getAnchorFrame(),
                                            nullptr,
                                            _landmark_ptr,
+                                           _processor_ptr,
                                            _apply_loss_function, _status,
                                            _ftr_ptr->getCapturePtr()->getFramePtr()->getPPtr(),
                                            _ftr_ptr->getCapturePtr()->getFramePtr()->getOPtr(),
@@ -86,11 +90,6 @@ inline ConstraintAHP::ConstraintAHP(FeatureBasePtr   _ftr_ptr,
     distortion_ = (std::static_pointer_cast<SensorCamera>(_ftr_ptr->getCapturePtr()->getSensorPtr()))->getDistortionVector();
 }
 
-inline ConstraintAHP::~ConstraintAHP()
-{
-    //
-}
-
 inline Eigen::VectorXs ConstraintAHP::expectation() const
 {
     FrameBasePtr frm_current = getFeaturePtr()->getCapturePtr()->getFramePtr();
@@ -193,13 +192,14 @@ inline wolf::JacobianMethod ConstraintAHP::getJacobianMethod() const
     return JAC_AUTO;
 }
 
-inline wolf::ConstraintAHPPtr ConstraintAHP::create(FeatureBasePtr   _ftr_ptr,
-                                                    LandmarkAHPPtr   _lmk_ahp_ptr,
+inline wolf::ConstraintAHPPtr ConstraintAHP::create(const FeatureBasePtr&   _ftr_ptr,
+                                                    const LandmarkAHPPtr&   _lmk_ahp_ptr,
+                                                    const ProcessorBasePtr& _processor_ptr,
                                                     bool             _apply_loss_function,
                                                     ConstraintStatus _status)
 {
     // construct constraint
-    ConstraintAHPPtr ctr_ahp = std::make_shared<ConstraintAHP>(_ftr_ptr, _lmk_ahp_ptr, _apply_loss_function, _status);
+    ConstraintAHPPtr ctr_ahp = std::make_shared<ConstraintAHP>(_ftr_ptr, _lmk_ahp_ptr, _processor_ptr, _apply_loss_function, _status);
 
     // link it to wolf tree <-- these pointers cannot be set at construction time
     _lmk_ahp_ptr->getAnchorFrame()->addConstrainedBy(ctr_ahp);
diff --git a/src/constraint_analytic.cpp b/src/constraint_analytic.cpp
index b25d76b688d97b835c8bd9a73604f49c0991b3de..f6d5ab4f10132ebffd11a3a448a28c6ff22de236 100644
--- a/src/constraint_analytic.cpp
+++ b/src/constraint_analytic.cpp
@@ -13,20 +13,22 @@ ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, bool _apply_loss_func
     resizeVectors();
 }
 
-ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, FrameBasePtr _frame_ptr, bool _apply_loss_function, ConstraintStatus _status,
+ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, const FrameBasePtr& _frame_ptr, const ProcessorBasePtr& _processor_ptr,
+                                       bool _apply_loss_function, ConstraintStatus _status,
                                        StateBlockPtr _state0Ptr, StateBlockPtr _state1Ptr, StateBlockPtr _state2Ptr, StateBlockPtr _state3Ptr, StateBlockPtr _state4Ptr,
                                        StateBlockPtr _state5Ptr, StateBlockPtr _state6Ptr, StateBlockPtr _state7Ptr, StateBlockPtr _state8Ptr, StateBlockPtr _state9Ptr ) :
-            ConstraintBase(_tp, _frame_ptr, nullptr, nullptr, _apply_loss_function, _status),
+            ConstraintBase(_tp, _frame_ptr, nullptr, nullptr, _processor_ptr, _apply_loss_function, _status),
             state_ptr_vector_({_state0Ptr, _state1Ptr, _state2Ptr, _state3Ptr, _state4Ptr,
                                _state5Ptr, _state6Ptr, _state7Ptr, _state8Ptr, _state9Ptr})
 {
     resizeVectors();
 }
 
-ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, FeatureBasePtr _feature_ptr, bool _apply_loss_function, ConstraintStatus _status,
+ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, const FeatureBasePtr& _feature_ptr, const ProcessorBasePtr& _processor_ptr,
+                                       bool _apply_loss_function, ConstraintStatus _status,
                                        StateBlockPtr _state0Ptr, StateBlockPtr _state1Ptr, StateBlockPtr _state2Ptr, StateBlockPtr _state3Ptr, StateBlockPtr _state4Ptr,
                                        StateBlockPtr _state5Ptr, StateBlockPtr _state6Ptr, StateBlockPtr _state7Ptr, StateBlockPtr _state8Ptr, StateBlockPtr _state9Ptr ) :
-            ConstraintBase( _tp, nullptr, _feature_ptr, nullptr, _apply_loss_function, _status),
+            ConstraintBase( _tp, nullptr, _feature_ptr, nullptr, _processor_ptr, _apply_loss_function, _status),
             state_ptr_vector_({_state0Ptr, _state1Ptr, _state2Ptr, _state3Ptr, _state4Ptr,
                                _state5Ptr, _state6Ptr, _state7Ptr, _state8Ptr, _state9Ptr})
 {
@@ -34,23 +36,17 @@ ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, FeatureBasePtr _featu
 }
 
 
-ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, LandmarkBasePtr _landmark_ptr, bool _apply_loss_function, ConstraintStatus _status,
+ConstraintAnalytic::ConstraintAnalytic(ConstraintType _tp, const LandmarkBasePtr& _landmark_ptr, const ProcessorBasePtr& _processor_ptr,
+                                       bool _apply_loss_function, ConstraintStatus _status,
                                        StateBlockPtr _state0Ptr, StateBlockPtr _state1Ptr, StateBlockPtr _state2Ptr, StateBlockPtr _state3Ptr, StateBlockPtr _state4Ptr,
                                        StateBlockPtr _state5Ptr, StateBlockPtr _state6Ptr, StateBlockPtr _state7Ptr, StateBlockPtr _state8Ptr, StateBlockPtr _state9Ptr ) :
-            ConstraintBase( _tp, nullptr, nullptr, _landmark_ptr, _apply_loss_function, _status),
+            ConstraintBase( _tp, nullptr, nullptr, _landmark_ptr, _processor_ptr, _apply_loss_function, _status),
             state_ptr_vector_({_state0Ptr, _state1Ptr, _state2Ptr, _state3Ptr, _state4Ptr,
                                _state5Ptr, _state6Ptr, _state7Ptr, _state8Ptr, _state9Ptr})
 {
     resizeVectors();
 }
 
-
-ConstraintAnalytic::~ConstraintAnalytic()
-{
-    //
-}
-
-
 const std::vector<Scalar*> ConstraintAnalytic::getStateScalarPtrVector()
 {
     assert(state_ptr_vector_.size() > 0 && state_ptr_vector_.size() <= 10 && "Wrong state vector size in constraint, it should be between 1 and 10");
diff --git a/src/constraint_analytic.h b/src/constraint_analytic.h
index 063249896e683b6930cd4fe2d9f1343893f869f3..356b6556443612a2250727cef0951c4a1cb476ca 100644
--- a/src/constraint_analytic.h
+++ b/src/constraint_analytic.h
@@ -40,67 +40,77 @@ class ConstraintAnalytic: public ConstraintBase
          * Constructor of category CTR_FRAME
          *
          **/
-        ConstraintAnalytic(ConstraintType _tp, FrameBasePtr _frame_ptr, bool _apply_loss_function, ConstraintStatus _status,
-                         StateBlockPtr _state0Ptr,
-                         StateBlockPtr _state1Ptr = nullptr,
-                         StateBlockPtr _state2Ptr = nullptr,
-                         StateBlockPtr _state3Ptr = nullptr,
-                         StateBlockPtr _state4Ptr = nullptr,
-                         StateBlockPtr _state5Ptr = nullptr,
-                         StateBlockPtr _state6Ptr = nullptr,
-                         StateBlockPtr _state7Ptr = nullptr,
-                         StateBlockPtr _state8Ptr = nullptr,
-                         StateBlockPtr _state9Ptr = nullptr );
+        ConstraintAnalytic(ConstraintType _tp,
+                           const FrameBasePtr&     _frame_ptr,
+                           const ProcessorBasePtr& _processor_ptr,
+                           bool _apply_loss_function,
+                           ConstraintStatus _status,
+                           StateBlockPtr _state0Ptr,
+                           StateBlockPtr _state1Ptr = nullptr,
+                           StateBlockPtr _state2Ptr = nullptr,
+                           StateBlockPtr _state3Ptr = nullptr,
+                           StateBlockPtr _state4Ptr = nullptr,
+                           StateBlockPtr _state5Ptr = nullptr,
+                           StateBlockPtr _state6Ptr = nullptr,
+                           StateBlockPtr _state7Ptr = nullptr,
+                           StateBlockPtr _state8Ptr = nullptr,
+                           StateBlockPtr _state9Ptr = nullptr );
 
         /** \brief Constructor of category CTR_FEATURE
          *
          * Constructor of category CTR_FEATURE
          *
          **/
-        ConstraintAnalytic(ConstraintType _tp, FeatureBasePtr _feature_ptr, bool _apply_loss_function, ConstraintStatus _status,
-                         StateBlockPtr _state0Ptr,
-                         StateBlockPtr _state1Ptr = nullptr,
-                         StateBlockPtr _state2Ptr = nullptr,
-                         StateBlockPtr _state3Ptr = nullptr,
-                         StateBlockPtr _state4Ptr = nullptr,
-                         StateBlockPtr _state5Ptr = nullptr,
-                         StateBlockPtr _state6Ptr = nullptr,
-                         StateBlockPtr _state7Ptr = nullptr,
-                         StateBlockPtr _state8Ptr = nullptr,
-                         StateBlockPtr _state9Ptr = nullptr ) ;
+        ConstraintAnalytic(ConstraintType _tp,
+                           const FeatureBasePtr&   _feature_ptr,
+                           const ProcessorBasePtr& _processor_ptr,
+                           bool _apply_loss_function, ConstraintStatus _status,
+                           StateBlockPtr _state0Ptr,
+                           StateBlockPtr _state1Ptr = nullptr,
+                           StateBlockPtr _state2Ptr = nullptr,
+                           StateBlockPtr _state3Ptr = nullptr,
+                           StateBlockPtr _state4Ptr = nullptr,
+                           StateBlockPtr _state5Ptr = nullptr,
+                           StateBlockPtr _state6Ptr = nullptr,
+                           StateBlockPtr _state7Ptr = nullptr,
+                           StateBlockPtr _state8Ptr = nullptr,
+                           StateBlockPtr _state9Ptr = nullptr );
 
         /** \brief Constructor of category CTR_LANDMARK
          *
          * Constructor of category CTR_LANDMARK
          *
          **/
-        ConstraintAnalytic(ConstraintType _tp, LandmarkBasePtr _landmark_ptr, bool _apply_loss_function, ConstraintStatus _status,
-                         StateBlockPtr _state0Ptr,
-                         StateBlockPtr _state1Ptr = nullptr,
-                         StateBlockPtr _state2Ptr = nullptr,
-                         StateBlockPtr _state3Ptr = nullptr,
-                         StateBlockPtr _state4Ptr = nullptr,
-                         StateBlockPtr _state5Ptr = nullptr,
-                         StateBlockPtr _state6Ptr = nullptr,
-                         StateBlockPtr _state7Ptr = nullptr,
-                         StateBlockPtr _state8Ptr = nullptr,
-                         StateBlockPtr _state9Ptr = nullptr ) ;
-
-        virtual ~ConstraintAnalytic();
+        ConstraintAnalytic(ConstraintType _tp,
+                           const LandmarkBasePtr&  _landmark_ptr,
+                           const ProcessorBasePtr& _processor_ptr,
+                           bool _apply_loss_function, ConstraintStatus _status,
+                           StateBlockPtr _state0Ptr,
+                           StateBlockPtr _state1Ptr = nullptr,
+                           StateBlockPtr _state2Ptr = nullptr,
+                           StateBlockPtr _state3Ptr = nullptr,
+                           StateBlockPtr _state4Ptr = nullptr,
+                           StateBlockPtr _state5Ptr = nullptr,
+                           StateBlockPtr _state6Ptr = nullptr,
+                           StateBlockPtr _state7Ptr = nullptr,
+                           StateBlockPtr _state8Ptr = nullptr,
+                           StateBlockPtr _state9Ptr = nullptr );
+
+        virtual ~ConstraintAnalytic() = default;
 
         /** \brief Returns a vector of pointers to the state blocks
          *
          * Returns a vector of pointers to the state blocks in which this constraint depends
          *
          **/
-        virtual const std::vector<Scalar*> getStateScalarPtrVector();
+        virtual const std::vector<Scalar*> getStateScalarPtrVector() override;
 
         /** \brief Returns a vector of pointers to the states
          *
          * Returns a vector of pointers to the state in which this constraint depends
          *
          **/
-        virtual const std::vector<StateBlockPtr> getStateBlockPtrVector() const;
+        virtual const std::vector<StateBlockPtr> getStateBlockPtrVector() const override;
 
         /** \brief Returns a vector of sizes of the state blocks
          *
@@ -114,7 +124,7 @@ class ConstraintAnalytic: public ConstraintBase
          * Returns the constraint residual size
          *
          **/
-        virtual unsigned int getSize() const = 0;
+//        virtual unsigned int getSize() const = 0;
 
         /** \brief Evaluate the constraint given the input parameters and returning the residuals and jacobians
         **/
@@ -194,7 +204,7 @@ class ConstraintAnalytic: public ConstraintBase
          * Returns the jacobians computation method
          *
          **/
-        virtual JacobianMethod getJacobianMethod() const;
+        virtual JacobianMethod getJacobianMethod() const override;
 
     private:
         void resizeVectors();
diff --git a/src/constraint_autodiff.h b/src/constraint_autodiff.h
index 150ceff9092cd9628bae6313f7d86f8b7285b643..2b7c2ddc0e98404acd7da5bccecb95c6e62b5792 100644
--- a/src/constraint_autodiff.h
+++ b/src/constraint_autodiff.h
@@ -58,7 +58,13 @@ class ConstraintAutodiff: public ConstraintBase
     public:
         /** \brief Constructor valid for all categories (ABSOLUTE, FRAME, FEATURE, LANDMARK)
          **/
-        ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+        ConstraintAutodiff(ConstraintType _tp,
+                           const FrameBasePtr& _frame_other_ptr,
+                           const FeatureBasePtr& _feature_other_ptr,
+                           const LandmarkBasePtr& _landmark_other_ptr,
+                           const ProcessorBasePtr& _processor_ptr,
+                           bool _apply_loss_function,
+                           ConstraintStatus _status,
                            StateBlockPtr _state0Ptr,
                            StateBlockPtr _state1Ptr,
                            StateBlockPtr _state2Ptr,
@@ -69,7 +75,7 @@ class ConstraintAutodiff: public ConstraintBase
                            StateBlockPtr _state7Ptr,
                            StateBlockPtr _state8Ptr,
                            StateBlockPtr _state9Ptr) :
-            ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+            ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
             state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr,_state4Ptr,_state5Ptr,_state6Ptr,_state7Ptr,_state8Ptr,_state9Ptr}),
             residuals_jets_(new std::array<WolfJet, RES>),
             jets_0_(new std::array<WolfJet, B0>),
@@ -357,7 +363,13 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,0> : public Constra
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr,
@@ -367,7 +379,7 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,B6,B7,B8,0> : public Constra
                           StateBlockPtr _state6Ptr,
                           StateBlockPtr _state7Ptr,
                           StateBlockPtr _state8Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr,_state4Ptr,_state5Ptr,_state6Ptr,_state7Ptr,_state8Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -615,7 +627,13 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,B6,B7,0,0> : public Constrai
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr,
@@ -624,7 +642,7 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,B6,B7,0,0> : public Constrai
                           StateBlockPtr _state5Ptr,
                           StateBlockPtr _state6Ptr,
                           StateBlockPtr _state7Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr,_state4Ptr,_state5Ptr,_state6Ptr,_state7Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -861,7 +879,13 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,B6,0,0,0> : public Constrain
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr,
@@ -869,7 +893,7 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,B6,0,0,0> : public Constrain
                           StateBlockPtr _state4Ptr,
                           StateBlockPtr _state5Ptr,
                           StateBlockPtr _state6Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr,_state4Ptr,_state5Ptr,_state6Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -1095,14 +1119,20 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,B5,0,0,0,0> : public Constraint
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr,
                           StateBlockPtr _state3Ptr,
                           StateBlockPtr _state4Ptr,
                           StateBlockPtr _state5Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr,_state4Ptr,_state5Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -1316,13 +1346,19 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,B4,0,0,0,0,0> : public ConstraintB
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr,
                           StateBlockPtr _state3Ptr,
                           StateBlockPtr _state4Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr,_state4Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -1525,12 +1561,18 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,B3,0,0,0,0,0,0> : public ConstraintBa
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr,
                           StateBlockPtr _state3Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr,_state3Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -1722,11 +1764,17 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,B2,0,0,0,0,0,0,0> : public ConstraintBas
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr,
                           StateBlockPtr _state2Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr,_state2Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -1907,10 +1955,16 @@ class ConstraintAutodiff<CtrT,RES,B0,B1,0,0,0,0,0,0,0,0> : public ConstraintBase
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr,
                           StateBlockPtr _state1Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr,_state1Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>),
@@ -2080,9 +2134,15 @@ class ConstraintAutodiff<CtrT,RES,B0,0,0,0,0,0,0,0,0,0> : public ConstraintBase
 
    public:
 
-       ConstraintAutodiff(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status,
+       ConstraintAutodiff(ConstraintType _tp,
+                          const FrameBasePtr& _frame_other_ptr,
+                          const FeatureBasePtr& _feature_other_ptr,
+                          const LandmarkBasePtr& _landmark_other_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          bool _apply_loss_function,
+                          ConstraintStatus _status,
                           StateBlockPtr _state0Ptr) :
-           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _apply_loss_function, _status),
+           ConstraintBase(_tp, _frame_other_ptr, _feature_other_ptr, _landmark_other_ptr, _processor_ptr, _apply_loss_function, _status),
            state_ptrs_({_state0Ptr}),
            residuals_jets_(new std::array<WolfJet, RES>),
            jets_0_(new std::array<WolfJet, B0>)
diff --git a/src/constraint_base.cpp b/src/constraint_base.cpp
index db055687a49734f5860399ac2d96c727943024f0..368448a7413f621a3de5d9abba5f37303b2c1411 100644
--- a/src/constraint_base.cpp
+++ b/src/constraint_base.cpp
@@ -16,12 +16,16 @@ ConstraintBase::ConstraintBase(ConstraintType _tp, bool _apply_loss_function, Co
     apply_loss_function_(_apply_loss_function),
     frame_other_ptr_(), // nullptr
     feature_other_ptr_(), // nullptr
-    landmark_other_ptr_() // nullptr
+    landmark_other_ptr_(), // nullptr
+    processor_ptr_() // nullptr
 {
 //    std::cout << "constructed        +c" << id() << std::endl;
 }
 
-ConstraintBase::ConstraintBase(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status) :
+ConstraintBase::ConstraintBase(ConstraintType _tp,
+                               const FrameBasePtr& _frame_other_ptr, const FeatureBasePtr& _feature_other_ptr,
+                               const LandmarkBasePtr& _landmark_other_ptr, const ProcessorBasePtr& _processor_ptr,
+                               bool _apply_loss_function, ConstraintStatus _status) :
     NodeBase("CONSTRAINT", "Base"),
     feature_ptr_(),
     is_removing_(false),
@@ -31,16 +35,12 @@ ConstraintBase::ConstraintBase(ConstraintType _tp, FrameBasePtr _frame_other_ptr
     apply_loss_function_(_apply_loss_function),
     frame_other_ptr_(_frame_other_ptr),
     feature_other_ptr_(_feature_other_ptr),
-    landmark_other_ptr_(_landmark_other_ptr)
+    landmark_other_ptr_(_landmark_other_ptr),
+    processor_ptr_(_processor_ptr)
 {
 //    std::cout << "constructed        +c" << id() << std::endl;
 }
 
-ConstraintBase::~ConstraintBase()
-{
-//    std::cout << "destructed         -c" << id() << std::endl;
-}
-
 void ConstraintBase::remove()
 {
     if (!is_removing_)
diff --git a/src/constraint_base.h b/src/constraint_base.h
index 80483c1a56001dc95101ff896a8c80518b86e377..1fb15abab7408458304d8051bbd2471d181fa4d7 100644
--- a/src/constraint_base.h
+++ b/src/constraint_base.h
@@ -32,18 +32,25 @@ class ConstraintBase : public NodeBase, public std::enable_shared_from_this<Cons
         FrameBaseWPtr frame_other_ptr_;                    ///< FrameBase pointer (for category CTR_FRAME)
         FeatureBaseWPtr feature_other_ptr_;                ///< FeatureBase pointer (for category CTR_FEATURE)
         LandmarkBaseWPtr landmark_other_ptr_;              ///< LandmarkBase pointer (for category CTR_LANDMARK)
+        ProcessorBaseWPtr processor_ptr_;
 
     public:
 
         /** \brief Constructor of category CTR_ABSOLUTE
          **/
-        ConstraintBase(ConstraintType _tp, bool _apply_loss_function, ConstraintStatus _status);
+        ConstraintBase(ConstraintType _tp,  bool _apply_loss_function = false,
+                       ConstraintStatus _status = CTR_ACTIVE);
 
         /** \brief Constructor valid for all categories (FRAME, FEATURE, LANDMARK)
          **/
-        ConstraintBase(ConstraintType _tp, FrameBasePtr _frame_other_ptr, FeatureBasePtr _feature_other_ptr, LandmarkBasePtr _landmark_other_ptr, bool _apply_loss_function, ConstraintStatus _status);
+        ConstraintBase(ConstraintType _tp,
+                       const FrameBasePtr& _frame_other_ptr, const FeatureBasePtr& _feature_other_ptr,
+                       const LandmarkBasePtr& _landmark_other_ptr,
+                       const ProcessorBasePtr& _processor_ptr = nullptr,
+                       bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE);
+
+        virtual ~ConstraintBase() = default;
 
-        virtual ~ConstraintBase();
         void remove();
 
         unsigned int id() const;
@@ -132,6 +139,22 @@ class ConstraintBase : public NodeBase, public std::enable_shared_from_this<Cons
         LandmarkBasePtr getLandmarkOtherPtr() const;
         void setLandmarkOtherPtr(LandmarkBasePtr _lmk_o){landmark_other_ptr_ = _lmk_o;}
 
+        /**
+         * @brief getProcessor
+         * @return
+         */
+        ProcessorBasePtr getProcessor() const;
+
+        /**
+         * @brief setProcessor
+         * @param _processor_ptr
+         */
+        void setProcessor(const ProcessorBasePtr& _processor_ptr);
+
+        /**
+         * @brief getProblem
+         * @return
+         */
         ProblemPtr getProblem();
 
 };
@@ -224,5 +247,15 @@ inline LandmarkBasePtr ConstraintBase::getLandmarkOtherPtr() const
     return landmark_other_ptr_.lock();
 }
 
+inline ProcessorBasePtr ConstraintBase::getProcessor() const
+{
+  return processor_ptr_.lock();
+}
+
+inline void ConstraintBase::setProcessor(const ProcessorBasePtr& _processor_ptr)
+{
+  processor_ptr_ = _processor_ptr;
+}
+
 } // namespace wolf
 #endif
diff --git a/src/constraint_container.h b/src/constraint_container.h
index e763f7b24ad3102f56b96bdec87d74f60c29c969..7ec89a5a791810ddfb275d0b19dd6238a142d1d7 100644
--- a/src/constraint_container.h
+++ b/src/constraint_container.h
@@ -18,8 +18,12 @@ class ConstraintContainer: public ConstraintAutodiff<ConstraintContainer,3,2,1,2
 
 	public:
 
-	    ConstraintContainer(FeatureBasePtr _ftr_ptr, LandmarkContainerPtr _lmk_ptr, const unsigned int _corner, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-	        ConstraintAutodiff<ConstraintContainer,3,2,1,2,1>(CTR_CONTAINER, nullptr, nullptr, _lmk_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(),_ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr()),
+      ConstraintContainer(const FeatureBasePtr& _ftr_ptr,
+                          const LandmarkContainerPtr& _lmk_ptr,
+                          const ProcessorBasePtr& _processor_ptr,
+                          const unsigned int _corner,
+                          bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+            ConstraintAutodiff<ConstraintContainer,3,2,1,2,1>(CTR_CONTAINER, nullptr, nullptr, _lmk_ptr, _processor_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(),_ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr()),
 			lmk_ptr_(_lmk_ptr),
 			corner_(_corner)
 		{
@@ -29,10 +33,7 @@ class ConstraintContainer: public ConstraintAutodiff<ConstraintContainer,3,2,1,2
             std::cout << "new constraint container: corner idx = " << corner_ << std::endl;
 		}
 
-		virtual ~ConstraintContainer()
-		{
-			//std::cout << "deleting ConstraintContainer " << id() << std::endl;
-		}
+    virtual ~ConstraintContainer() = default;
 
 		LandmarkContainerPtr getLandmarkPtr()
 		{
@@ -115,24 +116,26 @@ class ConstraintContainer: public ConstraintAutodiff<ConstraintContainer,3,2,1,2
 			return true;
 		}
 
-        /** \brief Returns the jacobians computation method
-         *
-         * Returns the jacobians computation method
-         *
-         **/
-        virtual JacobianMethod getJacobianMethod() const
-        {
-            return JAC_AUTO;
-        }
-
-
-    public:
-        static ConstraintBasePtr create(FeatureBasePtr _feature_ptr, NodeBasePtr _correspondant_ptr)
-        {
-            unsigned int corner = 0; // Hard-coded, but this class is nevertheless deprecated.
-
-            return std::make_shared<ConstraintContainer>(_feature_ptr, std::static_pointer_cast<LandmarkContainer>(_correspondant_ptr), corner);
-        }
+    /** \brief Returns the jacobians computation method
+     *
+     * Returns the jacobians computation method
+     *
+     **/
+    virtual JacobianMethod getJacobianMethod() const override
+    {
+      return JAC_AUTO;
+    }
+
+
+  public:
+    static ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr,
+                                    const NodeBasePtr& _correspondant_ptr,
+                                    const ProcessorBasePtr& _processor_ptr = nullptr)
+    {
+      unsigned int corner = 0; // Hard-coded, but this class is nevertheless deprecated.
+
+      return std::make_shared<ConstraintContainer>(_feature_ptr, std::static_pointer_cast<LandmarkContainer>(_correspondant_ptr), _processor_ptr, corner);
+    }
 
 };
 
diff --git a/src/constraint_corner_2D.h b/src/constraint_corner_2D.h
index 67a2fe05a13f5e0268f8a01a0a3a477d6b091b8a..932d6756c7e6317b5e101eb0df6904a32341ae25 100644
--- a/src/constraint_corner_2D.h
+++ b/src/constraint_corner_2D.h
@@ -13,41 +13,41 @@ class ConstraintCorner2D: public ConstraintAutodiff<ConstraintCorner2D, 3,2,1,2,
 {
 	public:
 
-		ConstraintCorner2D(FeatureBasePtr _ftr_ptr, LandmarkCorner2DPtr _lmk_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-		    ConstraintAutodiff<ConstraintCorner2D,3,2,1,2,1>(CTR_CORNER_2D, nullptr, nullptr, _lmk_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(),_ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr())
-		{
-            setType("CORNER 2D");
-		}
-
-        virtual ~ConstraintCorner2D()
-        {
-            //std::cout << "deleting ConstraintCorner2D " << id() << std::endl;
-        }
-
-        LandmarkCorner2DPtr getLandmarkPtr()
-		{
-			return std::static_pointer_cast<LandmarkCorner2D>( landmark_other_ptr_.lock() );
-		}
-
-		template <typename T>
-        bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkP,
-                         const T* const _landmarkO, T* _residuals) const;
+    ConstraintCorner2D(const FeatureBasePtr _ftr_ptr,
+                       const LandmarkCorner2DPtr _lmk_ptr,
+                       const ProcessorBasePtr& _processor_ptr,
+                       bool _apply_loss_function = false,
+                       ConstraintStatus _status = CTR_ACTIVE) :
+        ConstraintAutodiff<ConstraintCorner2D,3,2,1,2,1>(CTR_CORNER_2D, nullptr, nullptr, _lmk_ptr, _processor_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(),_ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr())
+    {
+      setType("CORNER 2D");
+    }
+
+    virtual ~ConstraintCorner2D() = default;
+
+    LandmarkCorner2DPtr getLandmarkPtr()
+    {
+      return std::static_pointer_cast<LandmarkCorner2D>( landmark_other_ptr_.lock() );
+    }
+
+    template <typename T>
+    bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkP,
+                     const T* const _landmarkO, T* _residuals) const;
 
         /** \brief Returns the jacobians computation method
          *
          * Returns the jacobians computation method
          *
          **/
-        virtual JacobianMethod getJacobianMethod() const
-        {
-            return JAC_AUTO;
-        }
-
-    public:
-        static ConstraintBasePtr create(FeatureBasePtr _feature_ptr, NodeBasePtr _correspondant_ptr)
-        {
-            return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>(_correspondant_ptr) );
-        }
+    virtual JacobianMethod getJacobianMethod() const override
+    {
+      return JAC_AUTO;
+    }
+
+    static ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr, const ProcessorBasePtr& _processor_ptr = nullptr)
+    {
+      return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>(_correspondant_ptr), _processor_ptr);
+    }
 
 };
 
diff --git a/src/constraint_epipolar.h b/src/constraint_epipolar.h
index 58d1c72cc184f84925b345549b09ba3e2c745012..968ab5fb971d9baf56561fc7efdf0375a4159cc2 100644
--- a/src/constraint_epipolar.h
+++ b/src/constraint_epipolar.h
@@ -11,9 +11,13 @@ WOLF_PTR_TYPEDEFS(ConstraintEpipolar);
 class ConstraintEpipolar : public ConstraintBase
 {
     public:
-        ConstraintEpipolar(FeatureBasePtr _feature_ptr, FeatureBasePtr _feature_other_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE);
+        ConstraintEpipolar(const FeatureBasePtr& _feature_ptr,
+                           const FeatureBasePtr& _feature_other_ptr,
+                           const ProcessorBasePtr& _processor_ptr = nullptr,
+                           bool _apply_loss_function = false,
+                           ConstraintStatus _status = CTR_ACTIVE);
 
-        virtual ~ConstraintEpipolar();
+        virtual ~ConstraintEpipolar() = default;
 
 
         /** \brief Evaluate the constraint given the input parameters and returning the residuals and jacobians
@@ -25,42 +29,43 @@ class ConstraintEpipolar : public ConstraintBase
         virtual void evaluate(const std::vector<const Scalar*>& _states_ptr, Eigen::VectorXs& residual_, std::vector<Eigen::MatrixXs>& jacobians_) const{};
         /** \brief Returns the jacobians computation method
          **/
-        virtual JacobianMethod getJacobianMethod() const{return JAC_ANALYTIC;}
+        virtual JacobianMethod getJacobianMethod() const override {return JAC_ANALYTIC;}
 
         /** \brief Returns a vector of scalar pointers to the first element of all state blocks involved in the constraint
          **/
-        virtual const std::vector<Scalar*> getStateScalarPtrVector(){return std::vector<Scalar*>(0);}
+        virtual const std::vector<Scalar*> getStateScalarPtrVector() override {return std::vector<Scalar*>(0);}
 
         /** \brief Returns a vector of pointers to the states in which this constraint depends
          **/
-        virtual const std::vector<StateBlockPtr> getStateBlockPtrVector() const{return std::vector<StateBlockPtr>(0);}
+        virtual const std::vector<StateBlockPtr> getStateBlockPtrVector() const override {return std::vector<StateBlockPtr>(0);}
 
         /** \brief Returns the constraint residual size
          **/
-        virtual unsigned int getSize() const{return 0;}
+        virtual unsigned int getSize() const override {return 0;}
 
         /** \brief Returns the constraint states sizes
          **/
         virtual const std::vector<unsigned int> getStateSizes() const{return std::vector<unsigned int>({1});}
 
     public:
-        static wolf::ConstraintBasePtr create(FeatureBasePtr _feature_ptr, //
-                NodeBasePtr _correspondant_ptr);
+        static wolf::ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr,
+                                              const NodeBasePtr& _correspondant_ptr,
+                                              const ProcessorBasePtr& _processor_ptr = nullptr);
 
 };
 
-inline ConstraintEpipolar::ConstraintEpipolar(FeatureBasePtr _feature_ptr, FeatureBasePtr _feature_other_ptr, bool _apply_loss_function, ConstraintStatus _status) :
-        ConstraintBase(CTR_EPIPOLAR, nullptr, _feature_other_ptr, nullptr, _apply_loss_function, _status)
+inline ConstraintEpipolar::ConstraintEpipolar(const FeatureBasePtr& /*_feature_ptr*/, const FeatureBasePtr& _feature_other_ptr,
+                                              const ProcessorBasePtr& _processor_ptr,
+                                              bool _apply_loss_function, ConstraintStatus _status) :
+        ConstraintBase(CTR_EPIPOLAR, nullptr, _feature_other_ptr, nullptr, _processor_ptr, _apply_loss_function, _status)
 {
     setType("EPIPOLAR");
 }
 
-inline ConstraintEpipolar::~ConstraintEpipolar(){}
-
-inline wolf::ConstraintBasePtr ConstraintEpipolar::create(FeatureBasePtr _feature_ptr, //
-        NodeBasePtr _correspondant_ptr)
+inline wolf::ConstraintBasePtr ConstraintEpipolar::create(const FeatureBasePtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr,
+                                                          const ProcessorBasePtr& _processor_ptr)
 {
-    return std::make_shared<ConstraintEpipolar>(_feature_ptr, std::static_pointer_cast<FeatureBase>(_correspondant_ptr));
+    return std::make_shared<ConstraintEpipolar>(_feature_ptr, std::static_pointer_cast<FeatureBase>(_correspondant_ptr), _processor_ptr);
 }
 
 } // namespace wolf
diff --git a/src/constraint_fix.h b/src/constraint_fix.h
index e136981445b13bcd0f88ebb7b956f4c52cc2521b..8b140749947b8b88007d193150a63ede0d7d5eab 100644
--- a/src/constraint_fix.h
+++ b/src/constraint_fix.h
@@ -19,17 +19,13 @@ class ConstraintFix: public ConstraintAutodiff<ConstraintFix,3,2,1>
 {
     public:
         ConstraintFix(FeatureBasePtr _ftr_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-                ConstraintAutodiff<ConstraintFix, 3, 2, 1>(CTR_FIX, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
+                ConstraintAutodiff<ConstraintFix, 3, 2, 1>(CTR_FIX, nullptr, nullptr, nullptr, nullptr,_apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
         {
             setType("FIX");
 //            std::cout << "created ConstraintFix " << std::endl;
         }
 
-        virtual ~ConstraintFix()
-        {
-//            std::cout << "destructed ConstraintFix " << std::endl;
-            //
-        }
+        virtual ~ConstraintFix() = default;
 
         template<typename T>
         bool operator ()(const T* const _p, const T* const _o, T* _residuals) const;
@@ -39,7 +35,7 @@ class ConstraintFix: public ConstraintAutodiff<ConstraintFix,3,2,1>
          * Returns the jacobians computation method
          *
          **/
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
diff --git a/src/constraint_fix_3D.h b/src/constraint_fix_3D.h
index 29ab0b8a78546ccdc63d3f37137be6eb5b85b655..b64f63e699a6501543a7fdbd74c323e00a0c460e 100644
--- a/src/constraint_fix_3D.h
+++ b/src/constraint_fix_3D.h
@@ -18,20 +18,17 @@ class ConstraintFix3D: public ConstraintAutodiff<ConstraintFix3D,6,3,4>
     public:
 
         ConstraintFix3D(FeatureBasePtr _ftr_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintAutodiff<ConstraintFix3D,6,3,4>(CTR_FIX_3D, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
+            ConstraintAutodiff<ConstraintFix3D,6,3,4>(CTR_FIX_3D, nullptr, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
         {
             setType("FIX3D");
         }
 
-        virtual ~ConstraintFix3D()
-        {
-            //
-        }
+        virtual ~ConstraintFix3D() = default;
 
         template<typename T>
         bool operator ()(const T* const _p, const T* const _o, T* _residuals) const;
 
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
diff --git a/src/constraint_fix_bias.h b/src/constraint_fix_bias.h
new file mode 100644
index 0000000000000000000000000000000000000000..6afa4adc69435469cbdf3a8b3e0279164cc711d1
--- /dev/null
+++ b/src/constraint_fix_bias.h
@@ -0,0 +1,96 @@
+
+#ifndef CONSTRAINT_FIX_BIAS_H_
+#define CONSTRAINT_FIX_BIAS_H_
+
+//Wolf includes
+#include "constraint_autodiff.h"
+#include "frame_base.h"
+#include "frame_imu.h"
+#include "rotations.h"
+#include "feature_imu.h"
+
+//#include "ceres/jet.h"
+
+
+namespace wolf {
+    
+WOLF_PTR_TYPEDEFS(ConstraintFixBias);
+
+//class
+class ConstraintFixBias: public ConstraintAutodiff<ConstraintFixBias,6,3,3>
+{
+    public:
+        ConstraintFixBias(FeatureBasePtr _ftr_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+                ConstraintAutodiff<ConstraintFixBias, 6, 3, 3>(CTR_FIX_BIAS, nullptr, nullptr, nullptr, nullptr, _apply_loss_function, _status, std::static_pointer_cast<FrameIMU>(_ftr_ptr->getFramePtr())->getAccBiasPtr(),
+                                          std::static_pointer_cast<FrameIMU>(_ftr_ptr->getFramePtr())->getGyroBiasPtr())
+        {
+            setType("FIX BIAS");
+            // std::cout << "created ConstraintFixBias " << std::endl;
+        }
+
+        virtual ~ConstraintFixBias() = default;
+
+        template<typename T>
+        bool operator ()(const T* const _ab, const T* const _wb, T* _residuals) const;
+
+        /** \brief Returns the jacobians computation method
+         *
+         * Returns the jacobians computation method
+         *
+         **/
+        virtual JacobianMethod getJacobianMethod() const override
+        {
+            return JAC_AUTO;
+        }
+
+};
+
+template<typename T>
+inline bool ConstraintFixBias::operator ()(const T* const _ab, const T* const _wb, T* _residuals) const
+{
+    // measurement
+    Eigen::Matrix<T,6,1> meas =  getMeasurement().cast<T>();
+    Eigen::Matrix<T,3,1> ab(_ab);
+    Eigen::Matrix<T,3,1> wb(_wb);
+
+    // error
+    Eigen::Matrix<T,6,1> er;
+    er.head(3) = meas.head(3) - ab;
+    er.tail(3) = meas.tail(3) - wb;
+
+    // residual
+    Eigen::Map<Eigen::Matrix<T,6,1>> res(_residuals);
+    res = getFeaturePtr()->getMeasurementSquareRootInformationUpper().cast<T>() * er;
+
+    ////////////////////////////////////////////////////////
+    // print Jacobian. Uncomment this as you wish (remember to uncomment #include "ceres/jet.h" above):
+//    using ceres::Jet;
+//    Eigen::MatrixXs J(6,6);
+//    J.row(0) = ((Jet<Scalar, 3>)(er(0))).v;
+//    J.row(1) = ((Jet<Scalar, 3>)(er(1))).v;
+//    J.row(2) = ((Jet<Scalar, 3>)(er(2))).v;
+//    J.row(3) = ((Jet<Scalar, 3>)(er(3))).v;
+//    J.row(4) = ((Jet<Scalar, 3>)(er(4))).v;
+//    J.row(5) = ((Jet<Scalar, 3>)(er(5))).v;
+
+//    J.row(0) = ((Jet<Scalar, 3>)(res(0))).v;
+//    J.row(1) = ((Jet<Scalar, 3>)(res(1))).v;
+//    J.row(2) = ((Jet<Scalar, 3>)(res(2))).v;
+//    J.row(3) = ((Jet<Scalar, 3>)(res(3))).v;
+//    J.row(4) = ((Jet<Scalar, 3>)(res(4))).v;
+//    J.row(5) = ((Jet<Scalar, 3>)(res(5))).v;
+
+//    if (sizeof(er(0)) != sizeof(double))
+//    {
+//        std::cout << "ConstraintFixBias::Jacobian(c" << id() << ") = \n " << J << std::endl;
+//        std::cout << "ConstraintFixBias::Weighted Jacobian(c" << id() << ") = \n " << J << std::endl;
+//        std::cout << "Sqrt Info(c" << id() << ") = \n " << getMeasurementSquareRootInformationTransposed() << std::endl;
+//    }
+    ////////////////////////////////////////////////////////
+
+    return true;
+}
+
+} // namespace wolf
+
+#endif
diff --git a/src/constraint_gps_2D.h b/src/constraint_gps_2D.h
index f82f1b5ec7e766310ace049146bf02137271e49e..6a5948efb83027c2512c5be221d43f87c0829d69 100644
--- a/src/constraint_gps_2D.h
+++ b/src/constraint_gps_2D.h
@@ -16,15 +16,12 @@ class ConstraintGPS2D : public ConstraintAutodiff<ConstraintGPS2D, 2, 2>
     public:
 
         ConstraintGPS2D(FeatureBasePtr _ftr_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintAutodiff<ConstraintGPS2D, 2, 2>(CTR_GPS_FIX_2D, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr())
+            ConstraintAutodiff<ConstraintGPS2D, 2, 2>(CTR_GPS_FIX_2D, nullptr, nullptr, nullptr, nullptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr())
         {
             setType("GPS FIX 2D");
         }
 
-        virtual ~ConstraintGPS2D()
-        {
-            //
-        }
+        virtual ~ConstraintGPS2D() = default;
 
         template<typename T>
         bool operator ()(const T* const _x, T* _residuals) const;
@@ -34,7 +31,7 @@ class ConstraintGPS2D : public ConstraintAutodiff<ConstraintGPS2D, 2, 2>
          * Returns the jacobians computation method
          *
          **/
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
diff --git a/src/constraint_gps_pseudorange_2D.h b/src/constraint_gps_pseudorange_2D.h
index fc7b396dda3df657d74326229066efd3415ed1fa..0873355892d0d82b74c78a98fe238bbda034a2df 100644
--- a/src/constraint_gps_pseudorange_2D.h
+++ b/src/constraint_gps_pseudorange_2D.h
@@ -27,7 +27,7 @@ WOLF_PTR_TYPEDEFS(ConstraintGPSPseudorange2D);
 class ConstraintGPSPseudorange2D : public ConstraintAutodiff<ConstraintGPSPseudorange2D, 1, 2, 1, 3, 1, 3, 1>
 {
     public:
-        ConstraintGPSPseudorange2D(FeatureBasePtr _ftr_ptr, 
+        ConstraintGPSPseudorange2D(const FeatureBasePtr& _ftr_ptr,
                                    bool _apply_loss_function = false, 
                                    ConstraintStatus _status = CTR_ACTIVE) :
            ConstraintAutodiff<ConstraintGPSPseudorange2D, 1, 2, 1, 3, 1, 3, 1>(CTR_GPS_PR_2D,
@@ -47,10 +47,7 @@ class ConstraintGPSPseudorange2D : public ConstraintAutodiff<ConstraintGPSPseudo
             //std::cout << "ConstraintGPSPseudorange2D()  pr=" << pseudorange_ << "\tsat_pos=(" << sat_position_[0] << ", " << sat_position_[1] << ", " << sat_position_[2] << ")" << std::endl;
         }
 
-        virtual ~ConstraintGPSPseudorange2D()
-        {
-            //std::cout << "deleting ConstraintGPSPseudorange2D " << id() << std::endl;
-        }
+        virtual ~ConstraintGPSPseudorange2D() = default;
 
         template<typename T>
         bool operator ()(const T* const _vehicle_p, const T* const _vehicle_o, const T* const _sensor_p,
@@ -62,7 +59,7 @@ class ConstraintGPSPseudorange2D : public ConstraintAutodiff<ConstraintGPSPseudo
         * Returns the jacobians computation method
         *
         **/
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
diff --git a/src/constraint_gps_pseudorange_3D.h b/src/constraint_gps_pseudorange_3D.h
index 85fc476230a08c9486984847680612a6c9e8426b..47e4d95ffc0a263ec2215742e473efa3165fac4d 100644
--- a/src/constraint_gps_pseudorange_3D.h
+++ b/src/constraint_gps_pseudorange_3D.h
@@ -46,12 +46,7 @@ class ConstraintGPSPseudorange3D: public ConstraintAutodiff<ConstraintGPSPseudor
         }
 
 
-        virtual ~ConstraintGPSPseudorange3D()
-        {
-            //std::cout << "deleting ConstraintGPSPseudorange3D " << id() << std::endl;
-        }
-
-
+        virtual ~ConstraintGPSPseudorange3D() = default;
 
         template<typename T>
         bool operator ()(const T* const _vehicle_p, const T* const _vehicle_o, const T* const _sensor_p,
@@ -64,7 +59,7 @@ class ConstraintGPSPseudorange3D: public ConstraintAutodiff<ConstraintGPSPseudor
         * Returns the jacobians computation method
         *
         **/
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
diff --git a/src/constraint_imu.h b/src/constraint_imu.h
index fe3f7b733e9f41ca887f4d8f9b758bdeb00de70e..2a21202a2a8f38c3fc47342cdd244ed10b6a61a6 100644
--- a/src/constraint_imu.h
+++ b/src/constraint_imu.h
@@ -5,37 +5,109 @@
 #include "constraint_autodiff.h"
 #include "feature_imu.h"
 #include "frame_imu.h"
+#include "sensor_imu.h"
 #include "rotations.h"
 
+//Eigen include
+
 
 namespace wolf {
     
 WOLF_PTR_TYPEDEFS(ConstraintIMU);
 
 //class
-class ConstraintIMU : public ConstraintAutodiff<ConstraintIMU, 9, 3, 4, 3, 3, 3, 3, 4, 3>
+class ConstraintIMU : public ConstraintAutodiff<ConstraintIMU, 15, 3, 4, 3, 3, 3, 3, 4, 3, 3, 3>
 {
     public:
-        ConstraintIMU(FeatureIMUPtr _ftr_ptr, FrameIMUPtr _frame_ptr, bool _apply_loss_function = false,
+        ConstraintIMU(const FeatureIMUPtr& _ftr_ptr, const FrameIMUPtr& _frame_ptr,
+                      const ProcessorBasePtr& _processor_ptr = nullptr,
+                      bool _apply_loss_function = false,
                       ConstraintStatus _status = CTR_ACTIVE);
 
-        virtual ~ConstraintIMU();
+        virtual ~ConstraintIMU() = default;
 
+        /* \brief : compute the residual from the state blocks being iterated by the solver.
+            -> computes the expected measurement
+            -> compares the actual measurement with the expected one
+            -> weights the result with the covariance of the noise (residual = sqrt_info_matrix * err;)
+        */
         template<typename T>
-        bool operator ()(const T* const _p1, const T* const _o1, const T* const _v1, const T* const _b_a1, const T* _b_g1,
-                         const T* const _p2, const T* const _o2, const T* const _v2,
+        bool operator ()(const T* const _p1, const T* const _o1, const T* const _v1, const T* const _b_a1, const T* const _b_g1,
+                         const T* const _p2, const T* const _o2, const T* const _v2, const T* const _b_a2, const T* const _b_g2,
                          T* _residuals) const;
+        
+        /* \brief : compute the residual from the state blocks being iterated by the solver. (same as operator())
+            -> computes the expected measurement
+            -> compares the actual measurement with the expected one
+            -> weights the result with the covariance of the noise (residual = sqrt_info_matrix * err;)
+         * params :
+         * Vector3s _p1 : position in imu frame
+         * Vector4s _q1 : orientation quaternion in imu frame
+         * Vector3s _v1 : velocity in imu frame
+         * Vector3s _ab : accelerometer bias in imu frame
+         * Vector3s _wb : gyroscope bias in imu frame
+         * Vector3s _p2 : position in current frame
+         * Vector4s _q2 : orientation quaternion in current frame
+         * Vector3s _v2 : velocity in current frame
+         * Matrix<9,1, wolf::Scalar> _residuals : to retrieve residuals (POV) O is rotation vector... NOT A QUATERNION
+        */
+        template<typename D1, typename D2, typename D3>
+        bool getResiduals(const Eigen::MatrixBase<D1> & _p1, const Eigen::QuaternionBase<D2> & _q1, const Eigen::MatrixBase<D1> & _v1, const Eigen::MatrixBase<D1> & _ab1, const Eigen::MatrixBase<D1> & _wb1,
+                        const Eigen::MatrixBase<D1> & _p2, const Eigen::QuaternionBase<D2> & _q2, const Eigen::MatrixBase<D1> & _v2, const Eigen::MatrixBase<D1> & _ab2, const Eigen::MatrixBase<D1> & _wb2, const Eigen::MatrixBase<D3> & _residuals) const;
+
+        virtual JacobianMethod getJacobianMethod() const override;
+
+        /* Function expectation(...)
+         * params :
+         * Vector3s _p1 : position in imu frame
+         * Vector4s _q1 : orientation quaternion in imu frame
+         * Vector3s _v1 : velocity in imu frame
+         * Vector3s _ab : accelerometer bias in imu frame
+         * Vector3s _wb : gyroscope bias in imu frame
+         * Vector3s _p2 : position in current frame
+         * Vector4s _q2 : orientation quaternion in current frame
+         * Vector3s _v2 : velocity in current frame
+         * Matrix<10,1, wolf::Scalar> _expectation : to retrieve resulting expectation (PVQ)
+        */
+        template<typename D1, typename D2, typename D3>
+        void expectation(const Eigen::MatrixBase<D1> & _p1, const Eigen::QuaternionBase<D2> & _q1, const Eigen::MatrixBase<D1> & _v1, const Eigen::MatrixBase<D1> & _ab, const Eigen::MatrixBase<D1> & _wb,
+                        const Eigen::MatrixBase<D1> & _p2, const Eigen::QuaternionBase<D2> & _q2, const Eigen::MatrixBase<D1> & _v2, const Eigen::MatrixBase<D3> & _result) const;
 
-        virtual JacobianMethod getJacobianMethod() const;
+        /* \brief : return the expected value given the state blocks in the wolf tree
+            current frame data is taken from constraintIMU object.
+            IMU frame is taken from wolf tree
+        */
+        Eigen::VectorXs expectation() const
+        {
+            Eigen::Matrix<wolf::Scalar, 10, 1> exp;
+            FrameBasePtr frm_current    = getFeaturePtr()->getCapturePtr()->getFramePtr();
+            FrameBasePtr frm_imu     = getFrameOtherPtr();
+            
+            //get information on current_frame in the constraintIMU
+            const Eigen::Vector3s frame_current_pos  = dp_preint_;
+            const Eigen::Quaternions frame_current_ori  = dq_preint_;
+            const Eigen::Vector3s frame_current_vel  = dv_preint_;
+            const Eigen::Vector3s frame_current_ab  = acc_bias_preint_;
+            const Eigen::Vector3s frame_current_wb  = gyro_bias_preint_;
+            const Eigen::Vector3s frame_imu_pos   = (frm_imu->getPPtr()->getState());
+            const Eigen::Vector4s frame_imu_ori   = (frm_imu->getOPtr()->getState());
+            const Eigen::Vector3s frame_imu_vel  = (frm_imu->getVPtr()->getState());
+
+            Eigen::Quaternions frame_imu_ori_q(frame_imu_ori);
+            
+            expectation(frame_current_pos, frame_current_ori, frame_current_vel, frame_current_ab, frame_current_wb, frame_imu_pos, frame_imu_ori_q, frame_imu_vel, exp);
+            return exp;
+        }
 
     public:
-        static wolf::ConstraintBasePtr create(FeatureIMUPtr _feature_ptr, NodeBasePtr _correspondant_ptr);
+        static wolf::ConstraintBasePtr create(const FeatureIMUPtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr,
+                                              const ProcessorBasePtr& _processor_ptr);
 
     private:
         /// Preintegrated delta
         Eigen::Vector3s dp_preint_;
-        Eigen::Vector3s dv_preint_;
         Eigen::Quaternions dq_preint_;
+        Eigen::Vector3s dv_preint_;
 
         // Biases used during preintegration
         Eigen::Vector3s acc_bias_preint_;
@@ -51,19 +123,39 @@ class ConstraintIMU : public ConstraintAutodiff<ConstraintIMU, 9, 3, 4, 3, 3, 3,
         /// Metrics
         const wolf::Scalar dt_, dt_2_; ///< delta-time and delta-time-squared between keyframes
         const Eigen::Vector3s g_; ///< acceleration of gravity in World frame
+        const wolf::Scalar ab_rate_stdev_, wb_rate_stdev_; //stdev for standard_deviation (= sqrt(variance))
+        
+        /* bias covariance and bias residuals
+         *
+         * continuous bias covariance matrix for accelerometer would then be A_r = diag(ab_stdev_^2, ab_stdev_^2, ab_stdev_^2)
+         * To compute bias residuals, we will need to do (sqrt(A_r)).inverse() * ab_error
+         *
+         * In our case, we introduce time 'distance' in the computation of this residual (SEE FORSTER17), thus we have to use the discret covariance matrix
+         * discrete bias covariance matrix for accelerometer : A_r_dt = dt_ * A_r
+         * taking the square root for bias residuals : sqrt_A_r_dt = sqrt(dt_ * A_r) = sqrt(dt_) * sqrt(A_r)
+         * then with the inverse : sqrt_A_r_dt_inv = (sqrt(dt_ * A_r)).inverse() = (1/sqrt(dt_)) * sqrt(A_r).inverse()
+         *
+         * same logic for gyroscope bias
+         */ 
+        const Eigen::Matrix3s sqrt_A_r_dt_inv;
+        const Eigen::Matrix3s sqrt_W_r_dt_inv;
 };
 
-inline ConstraintIMU::ConstraintIMU(FeatureIMUPtr _ftr_ptr, FrameIMUPtr _frame_ptr, bool _apply_loss_function,
-                                    ConstraintStatus _status) :
-        ConstraintAutodiff<ConstraintIMU, 9, 3, 4, 3, 3, 3, 3, 4, 3>(CTR_IMU, _frame_ptr, nullptr, nullptr, _apply_loss_function, _status,
+inline ConstraintIMU::ConstraintIMU(const FeatureIMUPtr& _ftr_ptr,
+                                    const FrameIMUPtr& _frame_ptr,
+                                    const ProcessorBasePtr& _processor_ptr,
+                                    bool _apply_loss_function, ConstraintStatus _status) :
+        ConstraintAutodiff<ConstraintIMU,15, 3, 4, 3, 3, 3, 3, 4, 3, 3, 3>(CTR_IMU, _frame_ptr, nullptr, nullptr, _processor_ptr, _apply_loss_function, _status,
                                                     _frame_ptr->getPPtr(), _frame_ptr->getOPtr(), _frame_ptr->getVPtr(),
                                                     _frame_ptr->getAccBiasPtr(), _frame_ptr->getGyroBiasPtr(),
                                                     _ftr_ptr->getFramePtr()->getPPtr(),
                                                     _ftr_ptr->getFramePtr()->getOPtr(),
-                                                    _ftr_ptr->getFramePtr()->getVPtr()),
+                                                    _ftr_ptr->getFramePtr()->getVPtr(),
+                                                    std::static_pointer_cast<FrameIMU>(_ftr_ptr->getFramePtr())->getAccBiasPtr(),
+                                                    std::static_pointer_cast<FrameIMU>(_ftr_ptr->getFramePtr())->getGyroBiasPtr()),
         dp_preint_(_ftr_ptr->dp_preint_), // dp, dv, dq at preintegration time
-        dv_preint_(_ftr_ptr->dv_preint_),
         dq_preint_(_ftr_ptr->dq_preint_),
+        dv_preint_(_ftr_ptr->dv_preint_),
         acc_bias_preint_(_ftr_ptr->acc_bias_preint_), // state biases at preintegration time
         gyro_bias_preint_(_ftr_ptr->gyro_bias_preint_),
         dDp_dab_(_ftr_ptr->dDp_dab_), // Jacs of dp dv dq wrt biases
@@ -71,73 +163,161 @@ inline ConstraintIMU::ConstraintIMU(FeatureIMUPtr _ftr_ptr, FrameIMUPtr _frame_p
         dDp_dwb_(_ftr_ptr->dDp_dwb_),
         dDv_dwb_(_ftr_ptr->dDv_dwb_),
         dDq_dwb_(_ftr_ptr->dDq_dwb_),
-        dt_(_frame_ptr->getTimeStamp() - getFeaturePtr()->getFramePtr()->getTimeStamp()),
+        dt_(_ftr_ptr->getFramePtr()->getTimeStamp() - _frame_ptr->getTimeStamp()),
         dt_2_(dt_*dt_),
-        g_(wolf::gravity())
+        g_(wolf::gravity()),
+        ab_rate_stdev_(std::static_pointer_cast<SensorIMU>(_ftr_ptr->getCapturePtr()->getSensorPtr())->getAbRateStdev()),
+        wb_rate_stdev_(std::static_pointer_cast<SensorIMU>(_ftr_ptr->getCapturePtr()->getSensorPtr())->getWbRateStdev()),
+        sqrt_A_r_dt_inv((Eigen::Matrix3s::Identity() * ab_rate_stdev_ * sqrt(dt_)).inverse()),
+        sqrt_W_r_dt_inv((Eigen::Matrix3s::Identity() * wb_rate_stdev_ * sqrt(dt_)).inverse())
 
 {
     setType("IMU");
 }
 
-inline ConstraintIMU::~ConstraintIMU()
-{
-    //
-}
-
 template<typename T>
-inline bool ConstraintIMU::operator ()(const T* const _p1, const T* const _q1, const T* const _v1, const T* const _ab, const T* _wb,
-                                       const T* const _p2, const T* const _q2, const T* const _v2,
+inline bool ConstraintIMU::operator ()(const T* const _p1, const T* const _q1, const T* const _v1, const T* const _ab1, const T* const _wb1,
+                                       const T* const _p2, const T* const _q2, const T* const _v2, const T* const _ab2, const T* const _wb2,
                                        T* _residuals) const
 {
+    using namespace Eigen;
+
     // MAPS
-    Eigen::Map<const Eigen::Matrix<T,3,1> > p1(_p1);
-    Eigen::Map<const Eigen::Quaternion<T> > q1(_q1);
-    Eigen::Map<const Eigen::Matrix<T,3,1> > v1(_v1);
-    Eigen::Map<const Eigen::Matrix<T,3,1> > ab(_ab);
-    Eigen::Map<const Eigen::Matrix<T,3,1> > wb(_wb);
+    Map<const Matrix<T,3,1> > p1(_p1);
+    Map<const Quaternion<T> > q1(_q1);
+    Map<const Matrix<T,3,1> > v1(_v1);
+    Map<const Matrix<T,3,1> > ab1(_ab1);
+    Map<const Matrix<T,3,1> > wb1(_wb1);
 
-    Eigen::Map<const Eigen::Matrix<T,3,1> > p2(_p2);
-    Eigen::Map<const Eigen::Quaternion<T> > q2(_q2);
-    Eigen::Map<const Eigen::Matrix<T,3,1> > v2(_v2);
+    Map<const Matrix<T,3,1> > p2(_p2);
+    Map<const Quaternion<T> > q2(_q2);
+    Map<const Matrix<T,3,1> > v2(_v2);
+    Map<const Matrix<T,3,1> > ab2(_ab2);
+    Map<const Matrix<T,3,1> > wb2(_wb2);
 
-    Eigen::Map<Eigen::Matrix<T,10,1> > residuals(_residuals);
+    Map<Matrix<T,15,1> > residuals(_residuals);
 
 
     // Predict delta: d_pred = x2 (-) x1
-    Eigen::Matrix<T,3,1> dp_predict = q1.conjugate() * ( p2 - p1 - v1 * (T)dt_ - (T)0.5 * g_.cast<T>() * (T)dt_2_ );
-    Eigen::Matrix<T,3,1> dv_predict = q1.conjugate() * ( v2 - v1 - g_.cast<T>() * (T)dt_ );
-    Eigen::Quaternion<T> dq_predict = q1.conjugate() * q2;
+    Matrix<T,3,1> dp_predict = q1.conjugate() * ( p2 - p1 - v1 * (T)dt_ - (T)0.5 * g_.cast<T>() * (T)dt_2_ );
+    Matrix<T,3,1> dv_predict = q1.conjugate() * ( v2 - v1 - g_.cast<T>() * (T)dt_ );
+    Quaternion<T> dq_predict = q1.conjugate() * q2;
+
+    // Bias increments due to optimization updates
+    Matrix<T,3,1> dab1 = ab1 - acc_bias_preint_.cast<T>();
+    Matrix<T,3,1> dwb1 = wb1 - gyro_bias_preint_.cast<T>();
+
+    // Correct measured delta: delta_corr = delta + J_bias * bias_increment
+    Matrix<T,3,1> dp_correct = dp_preint_.cast<T>() + dDp_dab_.cast<T>() * dab1 + dDp_dwb_.cast<T>() * dwb1;
+    Matrix<T,3,1> dv_correct = dv_preint_.cast<T>() + dDv_dab_.cast<T>() * dab1 + dDv_dwb_.cast<T>() * dwb1;
+    Matrix<T,3,1> do_step    = dDq_dwb_  .cast<T>() * dwb1;
+    Quaternion<T> dq_correct = dq_preint_.cast<T>() * v2q(do_step);
+
+    // Delta error in minimal form: d_min = log(delta_pred (-) delta_corr)
+    // Note the Dt here is zero because it's the delta-time between the same time stamps!
+    // Note that we use P and V errors without rotation, since they should be zero anyway.
+    Matrix<T,3,1> dp_error   = dp_predict - dp_correct;
+    Matrix<T,3,1> dv_error   = dv_predict - dv_correct;
+    Matrix<T,3,1> do_error   = q2v(dq_correct.conjugate() * dq_predict); // In the name, 'o' of orientation, not 'q'
+    Matrix<T,3,1> ab_error(ab1 - ab2); //bias used for preintegration - bias in KeyFrame
+    Matrix<T,3,1> wb_error(wb1 - wb2);
+
+    Matrix<T,9,1> dpov_error((Matrix<T,9,1>() << dp_error, do_error, dv_error).finished());
+
+    // Assign to residuals vector
+    residuals.head(9)       = getMeasurementSquareRootInformationTransposed().cast<T>() * dpov_error;
+    residuals.segment(9,3)  = sqrt_A_r_dt_inv.cast<T>() * ab_error; // ab_residual = ( (1/sqrt(dt_)) * sqrt(A_r).inverse() ) * ab_error;
+    residuals.tail(3)       = sqrt_W_r_dt_inv.cast<T>() * wb_error; // wb_residual = ( (1/sqrt(dt_)) * sqrt(A_r).inverse() ) * wb_error;   
+
+    /*std::cout << *_p2 << std::endl;
+    std::cout << *_ab1 << "\t" << *_wb1 << std::endl;
+    std::cout << *_ab2 << "\t" << *_wb2 << std::endl;
+    std::cout << getMeasurementSquareRootInformationTransposed() << std::endl;
+    std::cout << *_residuals << std::endl;*/
+
+    return true;
+}
+
+template<typename D1, typename D2, typename D3>
+inline bool ConstraintIMU::getResiduals(const Eigen::MatrixBase<D1> & _p1, const Eigen::QuaternionBase<D2> & _q1, const Eigen::MatrixBase<D1> & _v1, const Eigen::MatrixBase<D1> & _ab1, const Eigen::MatrixBase<D1> & _wb1,
+                        const Eigen::MatrixBase<D1> & _p2, const Eigen::QuaternionBase<D2> & _q2, const Eigen::MatrixBase<D1> & _v2, const Eigen::MatrixBase<D1> & _ab2, const Eigen::MatrixBase<D1> & _wb2, const Eigen::MatrixBase<D3> & _residuals) const
+{
+    //needed typedefs
+    typedef typename D2::Scalar DataType;
+
+    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(D3, 15)
+
+    const Eigen::Matrix<DataType,3,1> ab1(_ab1);
+    const Eigen::Matrix<DataType,3,1> wb1(_wb1);
+    const Eigen::Matrix<DataType,3,1> ab2(_ab2);
+    const Eigen::Matrix<DataType,3,1> wb2(_wb2);
+    Eigen::Matrix<DataType,10,1> expected;
+    this->expectation(_p1, _q1, _v1, _ab1, _wb1, _p2, _q2, _v2, expected);
 
     // Correct measured delta: delta_corr = delta + J_bias * (bias - bias_measured)
-    Eigen::Matrix<T,3,1> dp_correct = dp_preint_.cast<T>() + dDp_dab_.cast<T>() * (ab - acc_bias_preint_.cast<T>()) + dDp_dwb_.cast<T>() * (wb - gyro_bias_preint_.cast<T>());
-    Eigen::Matrix<T,3,1> dv_correct = dv_preint_.cast<T>() + dDv_dab_.cast<T>() * (ab - acc_bias_preint_.cast<T>()) + dDv_dwb_.cast<T>() * (wb - gyro_bias_preint_.cast<T>());
-    Eigen::Matrix<T,3,1> do_step    = dDq_dwb_  .cast<T>() * (wb - gyro_bias_preint_.cast<T>());
-    Eigen::Quaternion<T> dq_correct = dq_preint_.cast<T>() * v2q(do_step);
+    Eigen::Matrix<DataType,3,1> dp_correct = dp_preint_.cast<DataType>() + dDp_dab_.cast<DataType>() * (ab1 - acc_bias_preint_.cast<DataType>()) + dDp_dwb_.cast<DataType>() * (wb1 - gyro_bias_preint_.cast<DataType>());
+    Eigen::Matrix<DataType,3,1> dv_correct = dv_preint_.cast<DataType>() + dDv_dab_.cast<DataType>() * (ab1 - acc_bias_preint_.cast<DataType>()) + dDv_dwb_.cast<DataType>() * (wb1 - gyro_bias_preint_.cast<DataType>());
+    Eigen::Matrix<DataType,3,1> do_step    = dDq_dwb_  .cast<DataType>() * (wb1 - gyro_bias_preint_.cast<DataType>());
+    Eigen::Quaternion<DataType> dq_correct = dq_preint_.cast<DataType>() * v2q(do_step);
 
     // Delta error in minimal form: d_min = log(delta_pred (-) delta_corr)
     // Note the Dt here is zero because it's the delta-time between the same time stamps!
-    Eigen::Matrix<T,3,1> dp_error   = dp_predict - dp_correct;
-    Eigen::Matrix<T,3,1> dv_error   = dv_predict - dv_correct;
-    Eigen::Matrix<T,3,1> do_error   = q2v(dq_correct.conjugate() * dq_predict); // In the name, 'o' of orientation, not 'q'
+    Eigen::Quaternion<DataType> dq_predict((expected.segment(3,4)).data());
+    Eigen::Matrix<DataType,3,1> dp_error   = expected.head(3) - dp_correct;
+    Eigen::Matrix<DataType,3,1> do_error   = q2v(dq_correct.conjugate() * dq_predict); // In the name, 'o' of orientation, not 'q'
+    Eigen::Matrix<DataType,3,1> dv_error   = expected.tail(3) - dv_correct;
+    Eigen::Matrix<DataType,3,1> ab_error(ab1 - ab2); // KF1.bias - KF2.bias
+    Eigen::Matrix<DataType,3,1> wb_error(wb1 - wb2);
+
+    Eigen::Matrix<DataType,9,1> dpov_error((Eigen::Matrix<DataType,9,1>() << dp_error, do_error, dv_error).finished());
+    Eigen::Matrix<DataType,9,1> dpov_error_w(getMeasurementSquareRootInformationTransposed().cast<DataType>()  * dpov_error);
 
     // Assign to residuals vector
-    residuals.head(3)       = dp_error;
-    residuals.segment(3,3)  = dv_error;
-    residuals.tail(3)       = do_error;
+    const_cast< Eigen::MatrixBase<D3>& > (_residuals).head(3)       = dpov_error_w.head(3);
+    const_cast< Eigen::MatrixBase<D3>& > (_residuals).segment(3,3)  = dpov_error_w.segment(3,3);
+    const_cast< Eigen::MatrixBase<D3>& > (_residuals).segment(6,3)  = dpov_error_w.tail(3);
+    const_cast< Eigen::MatrixBase<D3>& > (_residuals).segment(9,3)  = sqrt_A_r_dt_inv.cast<DataType>() * ab_error;
+    const_cast< Eigen::MatrixBase<D3>& > (_residuals).tail(3)       = sqrt_A_r_dt_inv.cast<DataType>() * wb_error;
 
     return true;
 }
 
+template<typename D1, typename D2, typename D3>
+inline void ConstraintIMU::expectation(const Eigen::MatrixBase<D1> & _p1, const Eigen::QuaternionBase<D2> & _q1, const Eigen::MatrixBase<D1> & _v1, const Eigen::MatrixBase<D1> & _ab, const Eigen::MatrixBase<D1> & _wb,
+                        const Eigen::MatrixBase<D1> & _p2, const Eigen::QuaternionBase<D2> & _q2, const Eigen::MatrixBase<D1> & _v2, const Eigen::MatrixBase<D3> & _result) const
+{
+    //needed typedefs
+    typedef typename D2::Vector3 Vector3Map;
+    typedef typename D2::Scalar DataType;
+    typedef Eigen::Map <Eigen::Matrix<DataType,4,1> > ConstVector4Map;
+
+    //instead of maps we use static_asserts from eigen to detect size at compile time
+    //check entry sizes
+    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(D1, 3)
+    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(D3, 10)
+     
+    // Predict delta: d_pred = x2 (-) x1
+    Vector3Map dp_predict = (_q1.conjugate() * ( _p2 - _p1 - _v1 * (DataType)dt_ - (DataType)0.5 * g_.cast<DataType>() * (DataType)dt_2_ ));
+    Vector3Map dv_predict (_q1.conjugate() * ( _v2 - _v1 - g_.cast<DataType>() * (DataType)dt_ ));
+    Eigen::Quaternion<DataType> dq_predict (_q1.conjugate() * _q2);
+    ConstVector4Map dq_vec4(dq_predict.coeffs().data());
+
+    const_cast< Eigen::MatrixBase<D3>& > (_result).head(3) = dp_predict;
+    const_cast< Eigen::MatrixBase<D3>& > (_result).segment(3,4) = dq_vec4;
+    const_cast< Eigen::MatrixBase<D3>& > (_result).tail(3) = dv_predict;
+}
+
 inline JacobianMethod ConstraintIMU::getJacobianMethod() const
 {
     return JAC_AUTO;
 }
 
-inline wolf::ConstraintBasePtr ConstraintIMU::create(FeatureIMUPtr _feature_ptr, NodeBasePtr _correspondant_ptr)
+inline wolf::ConstraintBasePtr ConstraintIMU::create(const FeatureIMUPtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr, const ProcessorBasePtr& _processor_ptr)
 {
-    return std::make_shared<ConstraintIMU>(_feature_ptr, std::static_pointer_cast<FrameIMU>(_correspondant_ptr));
+    return std::make_shared<ConstraintIMU>(_feature_ptr, std::static_pointer_cast<FrameIMU>(_correspondant_ptr), _processor_ptr);
 }
 
+
 } // namespace wolf
 
 #endif
diff --git a/src/constraint_odom_2D.h b/src/constraint_odom_2D.h
index 023d98147f6fd26e1775933426c7b73816b3fe64..e592e322eea96a477d402816203f5e2140ec8c86 100644
--- a/src/constraint_odom_2D.h
+++ b/src/constraint_odom_2D.h
@@ -15,18 +15,17 @@ WOLF_PTR_TYPEDEFS(ConstraintOdom2D);
 class ConstraintOdom2D : public ConstraintAutodiff<ConstraintOdom2D, 3, 2, 1, 2, 1>
 {
     public:
-        ConstraintOdom2D(FeatureBasePtr _ftr_ptr, FrameBasePtr _frame_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintAutodiff<ConstraintOdom2D, 3, 2, 1, 2, 1>(CTR_ODOM_2D, _frame_ptr, nullptr, nullptr, _apply_loss_function, _status, _frame_ptr->getPPtr(), _frame_ptr->getOPtr(), _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
+        ConstraintOdom2D(const FeatureBasePtr& _ftr_ptr,
+                         const FrameBasePtr& _frame_ptr,
+                         const ProcessorBasePtr& _processor_ptr = nullptr,
+                         bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+             ConstraintAutodiff<ConstraintOdom2D, 3, 2, 1, 2, 1>(CTR_ODOM_2D, _frame_ptr, nullptr, nullptr, _processor_ptr, _apply_loss_function, _status, _frame_ptr->getPPtr(), _frame_ptr->getOPtr(), _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
         {
             setType("ODOM 2D");
 //            std::cout << "created ConstraintOdom2D " << std::endl;
         }
 
-        virtual ~ConstraintOdom2D()
-        {
-//            std::cout << "destructed ConstraintOdom2D " << std::endl;
-            //
-        }
+        virtual ~ConstraintOdom2D() = default;
 
         template<typename T>
         bool operator ()(const T* const _p1, const T* const _o1, const T* const _p2, const T* const _o2,
@@ -34,16 +33,15 @@ class ConstraintOdom2D : public ConstraintAutodiff<ConstraintOdom2D, 3, 2, 1, 2,
 
         /** \brief Returns the jacobians computation method
          **/
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
 
     public:
-        static wolf::ConstraintBasePtr create(FeatureBasePtr _feature_ptr, //
-                                            NodeBasePtr _correspondant_ptr)
+        static wolf::ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr, const NodeBasePtr& _correspondant_ptr, const ProcessorBasePtr& _processor_ptr)
         {
-            return std::make_shared<ConstraintOdom2D>(_feature_ptr, std::static_pointer_cast<FrameBase>(_correspondant_ptr) );
+            return std::make_shared<ConstraintOdom2D>(_feature_ptr, std::static_pointer_cast<FrameBase>(_correspondant_ptr), _processor_ptr);
         }
 
 };
diff --git a/src/constraint_odom_2D_analytic.h b/src/constraint_odom_2D_analytic.h
index 88ba510ae125ade012702c75c66eaf007baea5dd..9612a7bcb719668be8c8274b84a830ff17d62c36 100644
--- a/src/constraint_odom_2D_analytic.h
+++ b/src/constraint_odom_2D_analytic.h
@@ -13,16 +13,17 @@ WOLF_PTR_TYPEDEFS(ConstraintOdom2DAnalytic);
 class ConstraintOdom2DAnalytic : public ConstraintRelative2DAnalytic
 {
     public:
-        ConstraintOdom2DAnalytic(FeatureBasePtr _ftr_ptr, FrameBasePtr _frame_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintRelative2DAnalytic(_ftr_ptr, CTR_ODOM_2D, _frame_ptr, _apply_loss_function, _status)
+        ConstraintOdom2DAnalytic(const FeatureBasePtr& _ftr_ptr,
+                                 const FrameBasePtr& _frame_ptr,
+                                 const ProcessorBasePtr& _processor_ptr = nullptr,
+                                 bool _apply_loss_function = false,
+                                 ConstraintStatus _status = CTR_ACTIVE) :
+            ConstraintRelative2DAnalytic(_ftr_ptr, CTR_ODOM_2D, _frame_ptr, _processor_ptr, _apply_loss_function, _status)
         {
             setType("ODOM 2D ANALYTIC");
         }
 
-        virtual ~ConstraintOdom2DAnalytic()
-        {
-            //
-        }
+        virtual ~ConstraintOdom2DAnalytic() = default;
 
 //        /** \brief Returns the constraint residual size
 //         *
@@ -103,10 +104,11 @@ class ConstraintOdom2DAnalytic : public ConstraintRelative2DAnalytic
 
 
     public:
-        static wolf::ConstraintBasePtr create(FeatureBasePtr _feature_ptr, //
-                                            NodeBasePtr _correspondant_ptr)
+        static wolf::ConstraintBasePtr create(const FeatureBasePtr& _feature_ptr,
+                                              const NodeBasePtr& _correspondant_ptr,
+                                              const ProcessorBasePtr& _processor_ptr = nullptr)
         {
-            return std::make_shared<ConstraintOdom2DAnalytic>(_feature_ptr, std::static_pointer_cast<FrameBase>(_correspondant_ptr) );
+            return std::make_shared<ConstraintOdom2DAnalytic>(_feature_ptr, std::static_pointer_cast<FrameBase>(_correspondant_ptr), _processor_ptr);
         }
 
 };
diff --git a/src/constraint_odom_3D.h b/src/constraint_odom_3D.h
index a82fdd551e75b5e915c3b05adfc494dc8d3612e7..e315489b89a5196323b3837cfc9611295b2ecb6e 100644
--- a/src/constraint_odom_3D.h
+++ b/src/constraint_odom_3D.h
@@ -20,10 +20,15 @@ WOLF_PTR_TYPEDEFS(ConstraintOdom3D);
 class ConstraintOdom3D : public ConstraintAutodiff<ConstraintOdom3D,6,3,4,3,4>
 {
     public:
-        ConstraintOdom3D(FeatureBasePtr _ftr_current_ptr, FrameBasePtr _frame_past_ptr, bool _apply_loss_function = false,
+        ConstraintOdom3D(const FeatureBasePtr& _ftr_current_ptr,
+                         const FrameBasePtr& _frame_past_ptr,
+                         const ProcessorBasePtr& _processor_ptr = nullptr,
+                         bool _apply_loss_function = false,
                          ConstraintStatus _status = CTR_ACTIVE);
-        virtual ~ConstraintOdom3D();
-        JacobianMethod getJacobianMethod() const {return JAC_AUTO;}
+
+        virtual ~ConstraintOdom3D() = default;
+
+        JacobianMethod getJacobianMethod() const override {return JAC_AUTO;}
 
         template<typename T>
                 bool operator ()(const T* const _p_current,
@@ -69,12 +74,16 @@ inline void ConstraintOdom3D::printRes (const  Eigen::Matrix<Scalar,6,1> & r) co
 }
 
 
-inline ConstraintOdom3D::ConstraintOdom3D(FeatureBasePtr _ftr_current_ptr, FrameBasePtr _frame_past_ptr, bool _apply_loss_function,
+inline ConstraintOdom3D::ConstraintOdom3D(const FeatureBasePtr& _ftr_current_ptr,
+                                          const FrameBasePtr& _frame_past_ptr,
+                                          const ProcessorBasePtr& _processor_ptr,
+                                          bool _apply_loss_function,
                                           ConstraintStatus _status) :
         ConstraintAutodiff<ConstraintOdom3D, 6, 3, 4, 3, 4>(CTR_ODOM_3D,        // type
                                         _frame_past_ptr,    // frame other
                                         nullptr,            // feature other
                                         nullptr,            // landmark other
+                                        _processor_ptr,     // processor
                                         _apply_loss_function,
                                         _status,
                                         _ftr_current_ptr->getFramePtr()->getPPtr(), // current frame P
@@ -82,11 +91,7 @@ inline ConstraintOdom3D::ConstraintOdom3D(FeatureBasePtr _ftr_current_ptr, Frame
                                         _frame_past_ptr->getPPtr(), // past frame P
                                         _frame_past_ptr->getOPtr()) // past frame Q
 {
-    //
-}
-
-inline ConstraintOdom3D::~ConstraintOdom3D()
-{
+    setType("ODOM 3D");
     //
 }
 
diff --git a/src/constraint_point_2D.h b/src/constraint_point_2D.h
index a55f37c0205480ee2d0de200e6a65563b160a4a2..927743721fe640149df46d3a47931a4b1a7645dd 100644
--- a/src/constraint_point_2D.h
+++ b/src/constraint_point_2D.h
@@ -10,7 +10,9 @@ namespace wolf {
     
 WOLF_PTR_TYPEDEFS(ConstraintPoint2D);
     
-//class
+/**
+ * @brief The ConstraintPoint2D class
+ */
 class ConstraintPoint2D: public ConstraintAutodiff<ConstraintPoint2D, 2,2,1,2,1,2>
 {
     protected:
@@ -19,80 +21,99 @@ class ConstraintPoint2D: public ConstraintAutodiff<ConstraintPoint2D, 2,2,1,2,1,
         StateBlockPtr point_state_ptr_;
         Eigen::VectorXs measurement_;                   ///<  the measurement vector
         Eigen::MatrixXs measurement_covariance_;        ///<  the measurement covariance matrix
-        Eigen::MatrixXs measurement_sqrt_information_;        ///<  the squared root information matrix
+        Eigen::MatrixXs measurement_sqrt_information_;  ///<  the squared root information matrix
 
     public:
 
-		ConstraintPoint2D(FeaturePolyline2DPtr _ftr_ptr, LandmarkPolyline2DPtr _lmk_ptr, unsigned int _ftr_point_id, int _lmk_point_id, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-		    ConstraintAutodiff<ConstraintPoint2D,2,2,1,2,1,2>(CTR_POINT_2D, nullptr, nullptr, _lmk_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr(), _lmk_ptr->getPointStateBlockPtr(_lmk_point_id)),
-			feature_point_id_(_ftr_point_id), landmark_point_id_(_lmk_point_id), point_state_ptr_(_lmk_ptr->getPointStateBlockPtr(_lmk_point_id)), measurement_(_ftr_ptr->getPoints().col(_ftr_point_id)), measurement_covariance_(_ftr_ptr->getPointsCov().middleCols(_ftr_point_id*2,2))
-		{
-			//std::cout << "Constriant point: feature " << _ftr_ptr->id() << " landmark " << _lmk_ptr->id() << "(point " << _lmk_point_id << ")" << std::endl;
-			//std::cout << "landmark state block " << _lmk_ptr->getPointStateBlockPtr(_lmk_point_id)->getVector().transpose() << std::endl;
-            setType("POINT TO POINT 2D");
-            Eigen::LLT<Eigen::MatrixXs> lltOfA(measurement_covariance_); // compute the Cholesky decomposition of A
-            Eigen::MatrixXs measurement_sqrt_covariance = lltOfA.matrixU();
-            measurement_sqrt_information_ = measurement_sqrt_covariance.inverse().transpose(); // retrieve factor U  in the decomposition
-		}
-
-        virtual ~ConstraintPoint2D()
-        {
-            //std::cout << "deleting ConstraintPoint2D " << id() << std::endl;
-        }
-
-        LandmarkPolyline2DPtr getLandmarkPtr()
-		{
-			return std::static_pointer_cast<LandmarkPolyline2D>(landmark_other_ptr_.lock());
-		}
-
-        int getLandmarkPointId()
-        {
-            return landmark_point_id_;
-        }
-
-        unsigned int getFeaturePointId()
-        {
-            return feature_point_id_;
-        }
-
-        StateBlockPtr getLandmarkPointPtr()
-        {
-            return point_state_ptr_;
-        }
-
-		template <typename T>
-        bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkOriginP, const T* const _landmarkOriginO, const T* const _landmarkPoint, T* _residuals) const;
-
-        /** \brief Returns the jacobians computation method
+    ConstraintPoint2D(const FeaturePolyline2DPtr& _ftr_ptr,
+                      const LandmarkPolyline2DPtr& _lmk_ptr,
+                      const ProcessorBasePtr& _processor_ptr,
+                      unsigned int _ftr_point_id, int _lmk_point_id, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+        ConstraintAutodiff<ConstraintPoint2D,2,2,1,2,1,2>(CTR_POINT_2D, nullptr, nullptr, _lmk_ptr, _processor_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr(), _lmk_ptr->getPointStateBlockPtr(_lmk_point_id)),
+        feature_point_id_(_ftr_point_id), landmark_point_id_(_lmk_point_id), point_state_ptr_(_lmk_ptr->getPointStateBlockPtr(_lmk_point_id)), measurement_(_ftr_ptr->getPoints().col(_ftr_point_id)), measurement_covariance_(_ftr_ptr->getPointsCov().middleCols(_ftr_point_id*2,2))
+    {
+        //std::cout << "Constriant point: feature " << _ftr_ptr->id() << " landmark " << _lmk_ptr->id() << "(point " << _lmk_point_id << ")" << std::endl;
+        //std::cout << "landmark state block " << _lmk_ptr->getPointStateBlockPtr(_lmk_point_id)->getVector().transpose() << std::endl;
+        setType("POINT TO POINT 2D");
+        Eigen::LLT<Eigen::MatrixXs> lltOfA(measurement_covariance_); // compute the Cholesky decomposition of A
+        Eigen::MatrixXs measurement_sqrt_covariance = lltOfA.matrixU();
+        measurement_sqrt_information_ = measurement_sqrt_covariance.inverse().transpose(); // retrieve factor U  in the decomposition
+    }
+
+    virtual ~ConstraintPoint2D() = default;
+
+    /**
+     * @brief getLandmarkPtr
+     * @return
+     */
+    LandmarkPolyline2DPtr getLandmarkPtr()
+    {
+        return std::static_pointer_cast<LandmarkPolyline2D>(landmark_other_ptr_.lock());
+    }
+
+    /**
+     * @brief getLandmarkPointId
+     * @return
+     */
+    int getLandmarkPointId()
+    {
+      return landmark_point_id_;
+    }
+
+    /**
+     * @brief getFeaturePointId
+     * @return
+     */
+    unsigned int getFeaturePointId()
+    {
+      return feature_point_id_;
+    }
+
+    /**
+     * @brief getLandmarkPointPtr
+     * @return
+     */
+    StateBlockPtr getLandmarkPointPtr()
+    {
+      return point_state_ptr_;
+    }
+
+    /**
+     *
+     */
+    template <typename T>
+    bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkOriginP, const T* const _landmarkOriginO, const T* const _landmarkPoint, T* _residuals) const;
+
+    /** \brief Returns the jacobians computation method
          *
          * Returns the jacobians computation method
          *
          **/
-        virtual JacobianMethod getJacobianMethod() const
-        {
-            return JAC_AUTO;
-        }
+    virtual JacobianMethod getJacobianMethod() const override
+    {
+      return JAC_AUTO;
+    }
 
-        /** \brief Returns a reference to the feature measurement
+    /** \brief Returns a reference to the feature measurement
          **/
-        virtual const Eigen::VectorXs& getMeasurement() const
-        {
-            return measurement_;
-        }
+    virtual const Eigen::VectorXs& getMeasurement() const override
+    {
+      return measurement_;
+    }
 
-        /** \brief Returns a reference to the feature measurement covariance
+    /** \brief Returns a reference to the feature measurement covariance
          **/
-        virtual const Eigen::MatrixXs& getMeasurementCovariance() const
-        {
-            return measurement_covariance_;
-        }
+    virtual const Eigen::MatrixXs& getMeasurementCovariance() const override
+    {
+      return measurement_covariance_;
+    }
 
-        /** \brief Returns a reference to the feature measurement square root information
+    /** \brief Returns a reference to the feature measurement square root information
          **/
-        virtual const Eigen::MatrixXs& getMeasurementSquareRootInformationTransposed() const
-        {
-            return measurement_sqrt_information_;
-        }
+    virtual const Eigen::MatrixXs& getMeasurementSquareRootInformationTransposed() const override
+    {
+      return measurement_sqrt_information_;
+    }
 };
 
 template<typename T>
diff --git a/src/constraint_point_to_line_2D.h b/src/constraint_point_to_line_2D.h
index 492673ed05fa7bc94db75b00841d99ed30c8e209..c54b6ae50cb63ca1723817d688571bedd7f1f960 100644
--- a/src/constraint_point_to_line_2D.h
+++ b/src/constraint_point_to_line_2D.h
@@ -25,85 +25,86 @@ class ConstraintPointToLine2D: public ConstraintAutodiff<ConstraintPointToLine2D
 
     public:
 
-		ConstraintPointToLine2D(FeaturePolyline2DPtr _ftr_ptr, LandmarkPolyline2DPtr _lmk_ptr, unsigned int _ftr_point_id, int _lmk_point_id,  int _lmk_point_aux_id, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-		    ConstraintAutodiff<ConstraintPointToLine2D, 1,2,1,2,1,2,2>(CTR_POINT_TO_LINE_2D, nullptr, nullptr, _lmk_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr(), _lmk_ptr->getPointStateBlockPtr(_lmk_point_id), _lmk_ptr->getPointStateBlockPtr(_lmk_point_aux_id)),
-			landmark_point_id_(_lmk_point_id), landmark_point_aux_id_(_lmk_point_aux_id), feature_point_id_(_ftr_point_id), point_state_ptr_(_lmk_ptr->getPointStateBlockPtr(_lmk_point_id)), point_aux_state_ptr_(_lmk_ptr->getPointStateBlockPtr(_lmk_point_aux_id)), measurement_(_ftr_ptr->getPoints().col(_ftr_point_id)), measurement_covariance_(_ftr_ptr->getPointsCov().middleCols(_ftr_point_id*2,2))
-		{
-			//std::cout << "ConstraintPointToLine2D" << std::endl;
-            setType("POINT TO LINE 2D");
-            Eigen::LLT<Eigen::MatrixXs> lltOfA(measurement_covariance_); // compute the Cholesky decomposition of A
-            Eigen::MatrixXs measurement_sqrt_covariance = lltOfA.matrixU();
-            measurement_sqrt_information_ = measurement_sqrt_covariance.inverse().transpose(); // retrieve factor U  in the decomposition
-		}
-
-        virtual ~ConstraintPointToLine2D()
-        {
-            //std::cout << "deleting ConstraintPoint2D " << id() << std::endl;
-        }
-
-        LandmarkPolyline2DPtr getLandmarkPtr()
-		{
-			return std::static_pointer_cast<LandmarkPolyline2D>( landmark_other_ptr_.lock() );
-		}
-
-        int getLandmarkPointId()
-        {
-            return landmark_point_id_;
-        }
-
-        int getLandmarkPointAuxId()
-        {
-            return landmark_point_aux_id_;
-        }
-
-        unsigned int getFeaturePointId()
-        {
-            return feature_point_id_;
-        }
-
-        StateBlockPtr getLandmarkPointPtr()
-        {
-            return point_state_ptr_;
-        }
-
-        StateBlockPtr getLandmarkPointAuxPtr()
-        {
-            return point_state_ptr_;
-        }
-
-		template <typename T>
-        bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkOriginPosition, const T* const _landmarkOriginOrientation, const T* const _landmarkPoint, const T* const _landmarkPointAux, T* _residuals) const;
-
-        /** \brief Returns the jacobians computation method
+    ConstraintPointToLine2D(const FeaturePolyline2DPtr& _ftr_ptr,
+                            const LandmarkPolyline2DPtr& _lmk_ptr,
+                            const ProcessorBasePtr& _processor_ptr,
+                            unsigned int _ftr_point_id, int _lmk_point_id,  int _lmk_point_aux_id,
+                            bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+        ConstraintAutodiff<ConstraintPointToLine2D, 1,2,1,2,1,2,2>(CTR_POINT_TO_LINE_2D, nullptr, nullptr, _lmk_ptr, _processor_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _lmk_ptr->getPPtr(), _lmk_ptr->getOPtr(), _lmk_ptr->getPointStateBlockPtr(_lmk_point_id), _lmk_ptr->getPointStateBlockPtr(_lmk_point_aux_id)),
+        landmark_point_id_(_lmk_point_id), landmark_point_aux_id_(_lmk_point_aux_id), feature_point_id_(_ftr_point_id), point_state_ptr_(_lmk_ptr->getPointStateBlockPtr(_lmk_point_id)), point_aux_state_ptr_(_lmk_ptr->getPointStateBlockPtr(_lmk_point_aux_id)), measurement_(_ftr_ptr->getPoints().col(_ftr_point_id)), measurement_covariance_(_ftr_ptr->getPointsCov().middleCols(_ftr_point_id*2,2))
+    {
+        //std::cout << "ConstraintPointToLine2D" << std::endl;
+        setType("POINT TO LINE 2D");
+        Eigen::LLT<Eigen::MatrixXs> lltOfA(measurement_covariance_); // compute the Cholesky decomposition of A
+        Eigen::MatrixXs measurement_sqrt_covariance = lltOfA.matrixU();
+        measurement_sqrt_information_ = measurement_sqrt_covariance.inverse().transpose(); // retrieve factor U  in the decomposition
+    }
+
+    virtual ~ConstraintPointToLine2D() = default;
+
+    LandmarkPolyline2DPtr getLandmarkPtr()
+    {
+      return std::static_pointer_cast<LandmarkPolyline2D>( landmark_other_ptr_.lock() );
+    }
+
+    int getLandmarkPointId()
+    {
+      return landmark_point_id_;
+    }
+
+    int getLandmarkPointAuxId()
+    {
+      return landmark_point_aux_id_;
+    }
+
+    unsigned int getFeaturePointId()
+    {
+      return feature_point_id_;
+    }
+
+    StateBlockPtr getLandmarkPointPtr()
+    {
+      return point_state_ptr_;
+    }
+
+    StateBlockPtr getLandmarkPointAuxPtr()
+    {
+      return point_state_ptr_;
+    }
+
+    template <typename T>
+    bool operator ()(const T* const _robotP, const T* const _robotO, const T* const _landmarkOriginPosition, const T* const _landmarkOriginOrientation, const T* const _landmarkPoint, const T* const _landmarkPointAux, T* _residuals) const;
+
+    /** \brief Returns the jacobians computation method
          *
          * Returns the jacobians computation method
          *
          **/
-        virtual JacobianMethod getJacobianMethod() const
-        {
-            return JAC_AUTO;
-        }
+    virtual JacobianMethod getJacobianMethod() const override
+    {
+      return JAC_AUTO;
+    }
 
-        /** \brief Returns a reference to the feature measurement
+    /** \brief Returns a reference to the feature measurement
          **/
-        virtual const Eigen::VectorXs& getMeasurement() const
-        {
-            return measurement_;
-        }
+    virtual const Eigen::VectorXs& getMeasurement() const override
+    {
+      return measurement_;
+    }
 
-        /** \brief Returns a reference to the feature measurement covariance
+    /** \brief Returns a reference to the feature measurement covariance
          **/
-        virtual const Eigen::MatrixXs& getMeasurementCovariance() const
-        {
-            return measurement_covariance_;
-        }
+    virtual const Eigen::MatrixXs& getMeasurementCovariance() const override
+    {
+      return measurement_covariance_;
+    }
 
-        /** \brief Returns a reference to the feature measurement square root information
+    /** \brief Returns a reference to the feature measurement square root information
          **/
-        virtual const Eigen::MatrixXs& getMeasurementSquareRootInformationTransposed() const
-        {
-            return measurement_sqrt_information_;
-        }
+    virtual const Eigen::MatrixXs& getMeasurementSquareRootInformationTransposed() const override
+    {
+      return measurement_sqrt_information_;
+    }
 };
 
 template<typename T>
diff --git a/src/constraint_relative_2D_analytic.h b/src/constraint_relative_2D_analytic.h
index 43c736d2d2c0d2bb305ae28e5e35f6694284845d..f9b6fdc9d70234321f5c8c9a57b6d3b98c1258d6 100644
--- a/src/constraint_relative_2D_analytic.h
+++ b/src/constraint_relative_2D_analytic.h
@@ -17,36 +17,39 @@ class ConstraintRelative2DAnalytic : public ConstraintAnalytic
 
         /** \brief Constructor of category CTR_FRAME
          **/
-        ConstraintRelative2DAnalytic(FeatureBasePtr _ftr_ptr, ConstraintType _tp, FrameBasePtr _frame_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintAnalytic(_tp, _frame_ptr, _apply_loss_function, _status, _frame_ptr->getPPtr(), _frame_ptr->getOPtr(), _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
+        ConstraintRelative2DAnalytic(const FeatureBasePtr& _ftr_ptr, const ConstraintType& _tp, const FrameBasePtr& _frame_ptr,
+                                     const ProcessorBasePtr& _processor_ptr = nullptr,
+                                     bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+            ConstraintAnalytic(_tp, _frame_ptr, _processor_ptr, _apply_loss_function, _status, _frame_ptr->getPPtr(), _frame_ptr->getOPtr(), _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr())
         {
             //
         }
 
         /** \brief Constructor of category CTR_FEATURE
          **/
-        ConstraintRelative2DAnalytic(FeatureBasePtr _ftr_ptr, ConstraintType _tp, FeatureBasePtr _ftr_other_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintAnalytic(_tp, _ftr_other_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _ftr_other_ptr->getFramePtr()->getPPtr(), _ftr_other_ptr->getFramePtr()->getOPtr() )
+        ConstraintRelative2DAnalytic(const FeatureBasePtr& _ftr_ptr, const ConstraintType& _tp, const FeatureBasePtr& _ftr_other_ptr,
+                                     const ProcessorBasePtr& _processor_ptr = nullptr,
+                                     bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+            ConstraintAnalytic(_tp, _ftr_other_ptr, _processor_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _ftr_other_ptr->getFramePtr()->getPPtr(), _ftr_other_ptr->getFramePtr()->getOPtr() )
         {
             //
         }
 
         /** \brief Constructor of category CTR_LANDMARK
          **/
-        ConstraintRelative2DAnalytic(FeatureBasePtr _ftr_ptr, ConstraintType _tp, LandmarkBasePtr _landmark_ptr, bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
-            ConstraintAnalytic(_tp, _landmark_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _landmark_ptr->getPPtr(), _landmark_ptr->getOPtr())
+        ConstraintRelative2DAnalytic(const FeatureBasePtr& _ftr_ptr, const ConstraintType& _tp, const LandmarkBasePtr& _landmark_ptr,
+                                     const ProcessorBasePtr& _processor_ptr = nullptr,
+                                     bool _apply_loss_function = false, ConstraintStatus _status = CTR_ACTIVE) :
+            ConstraintAnalytic(_tp, _landmark_ptr, _processor_ptr, _apply_loss_function, _status, _ftr_ptr->getFramePtr()->getPPtr(), _ftr_ptr->getFramePtr()->getOPtr(), _landmark_ptr->getPPtr(), _landmark_ptr->getOPtr())
         {
             //
         }
 
-        virtual ~ConstraintRelative2DAnalytic()
-        {
-            //
-        }
+        virtual ~ConstraintRelative2DAnalytic() = default;
 
         /** \brief Returns the constraint residual size
          **/
-        virtual unsigned int getSize() const
+        virtual unsigned int getSize() const override
         {
             return 3;
         }
@@ -81,7 +84,7 @@ class ConstraintRelative2DAnalytic : public ConstraintAnalytic
 
         /** \brief Returns the jacobians computation method
          **/
-        virtual JacobianMethod getJacobianMethod() const
+        virtual JacobianMethod getJacobianMethod() const override
         {
             return JAC_AUTO;
         }
diff --git a/src/examples/CMakeLists.txt b/src/examples/CMakeLists.txt
index 022041a5a07228cea66ad0b1fb56ec66f3aa0891..042e149a58554acd158ee141dd2863baf583f0bc 100644
--- a/src/examples/CMakeLists.txt
+++ b/src/examples/CMakeLists.txt
@@ -145,8 +145,6 @@ IF(OpenCV_FOUND)
 
 ENDIF(OpenCV_FOUND)
 
-
-
 # Processor Tracker Feature test
 ADD_EXECUTABLE(test_processor_tracker_feature test_processor_tracker_feature.cpp)
 TARGET_LINK_LIBRARIES(test_processor_tracker_feature ${PROJECT_NAME})
@@ -167,6 +165,26 @@ TARGET_LINK_LIBRARIES(test_processor_imu ${PROJECT_NAME})
 #ADD_EXECUTABLE(test_processor_imu_jacobians test_processor_imu_jacobians.cpp)
 #TARGET_LINK_LIBRARIES(test_processor_imu_jacobians ${PROJECT_NAME})
 
+# Test IMU using printed Dock
+ADD_EXECUTABLE(test_imuDock test_imuDock.cpp)
+TARGET_LINK_LIBRARIES(test_imuDock ${PROJECT_NAME})
+
+# Test IMU with auto KF generation (Humanoids 20017)
+ADD_EXECUTABLE(test_imuDock_autoKFs test_imuDock_autoKFs.cpp)
+TARGET_LINK_LIBRARIES(test_imuDock_autoKFs ${PROJECT_NAME})
+
+# ConstraintIMU - factors test
+ADD_EXECUTABLE(test_imu_constrained0 test_imu_constrained0.cpp)
+TARGET_LINK_LIBRARIES(test_imu_constrained0 ${PROJECT_NAME})
+
+# IMU - Offline plateform test
+ADD_EXECUTABLE(test_imuPlateform_Offline test_imuPlateform_Offline.cpp)
+TARGET_LINK_LIBRARIES(test_imuPlateform_Offline ${PROJECT_NAME})
+
+# IMU - constraintIMU
+#ADD_EXECUTABLE(test_constraint_imu test_constraint_imu.cpp)
+#TARGET_LINK_LIBRARIES(test_constraint_imu ${PROJECT_NAME})
+
 # IF (laser_scan_utils_FOUND)
 #     ADD_EXECUTABLE(test_capture_laser_2D test_capture_laser_2D.cpp)
 #     TARGET_LINK_LIBRARIES(test_capture_laser_2D ${PROJECT_NAME})
diff --git a/src/examples/processor_imu.yaml b/src/examples/processor_imu.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..8a3aaf4708b56c97615fabf37962c0ea1db658bf
--- /dev/null
+++ b/src/examples/processor_imu.yaml
@@ -0,0 +1,8 @@
+processor type: "IMU"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+processor name: "Main imu"        # This is ignored. The name provided to the SensorFactory prevails
+keyframe vote:
+    max time span:      2.0   # seconds
+    max buffer length:  20000    # motion deltas
+    dist traveled:      2.0   # meters
+    angle turned:       0.2   # radians (1 rad approx 57 deg, approx 60 deg)
+    voting_active:      false
\ No newline at end of file
diff --git a/src/examples/processor_imu_t1.yaml b/src/examples/processor_imu_t1.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..9924b3ddd020333ef9d5f907f9a284db9c78166e
--- /dev/null
+++ b/src/examples/processor_imu_t1.yaml
@@ -0,0 +1,8 @@
+processor type: "IMU"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+processor name: "Main imu"        # This is ignored. The name provided to the SensorFactory prevails
+keyframe vote:
+    max time span:      0.9999   # seconds
+    max buffer length:  10000    # motion deltas
+    dist traveled:      10000   # meters
+    angle turned:       10000   # radians (1 rad approx 57 deg, approx 60 deg)
+    voting_active:      true
\ No newline at end of file
diff --git a/src/examples/processor_imu_t6.yaml b/src/examples/processor_imu_t6.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..7313a387eea81d7fd6bcd6ad1ff888c6c9962522
--- /dev/null
+++ b/src/examples/processor_imu_t6.yaml
@@ -0,0 +1,8 @@
+processor type: "IMU"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+processor name: "Main imu"        # This is ignored. The name provided to the SensorFactory prevails
+keyframe vote:
+    max time span:      5.9999   # seconds
+    max buffer length:  10000    # motion deltas
+    dist traveled:      10000   # meters
+    angle turned:       10000   # radians (1 rad approx 57 deg, approx 60 deg)
+    voting_active:      true
\ No newline at end of file
diff --git a/src/examples/sensor_imu.yaml b/src/examples/sensor_imu.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..66b81a5288877362753612f7aa4b9222da009e8d
--- /dev/null
+++ b/src/examples/sensor_imu.yaml
@@ -0,0 +1,9 @@
+sensor type: "IMU"             # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+sensor name: "Main IMU"        # This is ignored. The name provided to the SensorFactory prevails
+motion variances: 
+    a_noise:                0.053     # standard deviation of Acceleration noise (same for all the axis) in m/s2
+    w_noise:                0.0011    # standard deviation of Gyroscope noise (same for all the axis) in rad/sec
+    ab_initial_stdev:       0.800     # m/s2    - initial bias 
+    wb_initial_stdev:       0.350     # rad/sec - initial bias 
+    ab_rate_stdev:          0.1       # m/s2/sqrt(s)           
+    wb_rate_stdev:          0.0400    # rad/s/sqrt(s)
\ No newline at end of file
diff --git a/src/examples/sensor_odom_3D_HQ.yaml b/src/examples/sensor_odom_3D_HQ.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..08945ef842e46f28642f1be63ca95850b618a35e
--- /dev/null
+++ b/src/examples/sensor_odom_3D_HQ.yaml
@@ -0,0 +1,8 @@
+sensor type: "ODOM 3D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
+sensor name: "Main odometer"        # This is ignored. The name provided to the SensorFactory prevails
+motion variances: 
+    disp_to_disp:   0.000001  # m^2   / m
+    disp_to_rot:    0.000001  # rad^2 / m
+    rot_to_rot:     0.000001  # rad^2 / rad
+    min_disp_var:   0.00000001  # m^2
+    min_rot_var:    0.00000001  # rad^2
\ No newline at end of file
diff --git a/src/examples/test_constraint_AHP.cpp b/src/examples/test_constraint_AHP.cpp
index dc2d89fb9aa871693d5e618259b74615571cb656..91a2ba19e7f3aae58cbefca746a9dc4f9fcd8641 100644
--- a/src/examples/test_constraint_AHP.cpp
+++ b/src/examples/test_constraint_AHP.cpp
@@ -43,7 +43,7 @@ int main()
 
     // PROCESSOR
     // one-liner API
-    wolf_problem_ptr_->installProcessor("IMAGE LANDMARK", "ORB", "PinHole", wolf_root + "/src/examples/processor_image_ORB.yaml");
+    ProcessorBasePtr processor_ptr = wolf_problem_ptr_->installProcessor("IMAGE LANDMARK", "ORB", "PinHole", wolf_root + "/src/examples/processor_image_ORB.yaml");
 
 
     // create the current frame
@@ -118,7 +118,7 @@ int main()
 
 
     // Create the constraint
-    ConstraintAHPPtr constraint_ptr = std::make_shared<ConstraintAHP>(feat_point_image_ptr, std::static_pointer_cast<LandmarkAHP>(landmark));
+    ConstraintAHPPtr constraint_ptr = std::make_shared<ConstraintAHP>(feat_point_image_ptr, std::static_pointer_cast<LandmarkAHP>(landmark), processor_ptr);
 
     feat_point_image_ptr->addConstraint(constraint_ptr);
     std::cout << "Constraint AHP created" << std::endl;
diff --git a/src/examples/test_constraint_imu.cpp b/src/examples/test_constraint_imu.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e2f1458703faa24acf2a98f4ec3198327fbaf81d
--- /dev/null
+++ b/src/examples/test_constraint_imu.cpp
@@ -0,0 +1,281 @@
+//Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "sensor_imu.h"
+#include "capture_imu.h"
+#include "constraint_odom_3D.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu.h"
+#include "capture_fix.h"
+#include "ceres_wrapper/ceres_manager.h"
+
+//#define DEBUG_RESULTS
+
+int main(int argc, char** argv)
+{
+    using namespace wolf;
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+
+    std::cout << std::endl << "==================== test_constraint_imu ======================" << std::endl;
+
+    bool c0(false), c1(false);// c2(true), c3(true), c4(true);
+    // Wolf problem
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+    Eigen::VectorXs IMU_extrinsics(7);
+    IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot
+    SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, shared_ptr<IntrinsicsBase>());
+    wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", "");
+
+    // Ceres wrappers
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+    // Time and data variables
+    TimeStamp t;
+    Eigen::Vector6s data_;
+    Scalar mpu_clock = 0;
+
+    t.set(mpu_clock);
+
+    // Set the origin
+    Eigen::VectorXs x0(16);
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,.001,  0,0,.002; // Try some non-zero biases
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(x0, t); //this also creates a keyframe at origin
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix(); //fix the keyframe at origin
+
+    TimeStamp ts(0);
+    Eigen::VectorXs origin_state = x0;
+    
+    // Create one capture to store the IMU data arriving from (sensor / callback / file / etc.)
+    CaptureIMUPtr imu_ptr( std::make_shared<CaptureIMU>(t, sensor_ptr, data_, Eigen::Matrix6s::Identity()) );
+    imu_ptr->setFramePtr(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back());
+
+
+    // set variables
+    using namespace std;
+    Eigen::VectorXs state_vec;
+    Eigen::VectorXs delta_preint;
+    //FrameIMUPtr last_frame;
+    Eigen::Matrix<wolf::Scalar,9,9> delta_preint_cov;
+
+    //process data
+    mpu_clock = 0.001003;
+    //data_ << 0.579595, -0.143701, 9.939331, 0.127445, 0.187814, -0.055003;
+    data_ << 0.0, 0.0, 9.81, 0.0, 0.0, 0.0;
+    t.set(mpu_clock);
+    // assign data to capture
+    imu_ptr->setData(data_);
+    imu_ptr->setTimeStamp(t);
+    // process data in capture
+    sensor_ptr->process(imu_ptr);
+
+    if(c0){
+    /// ******************************************************************************************** ///
+    /// constraint creation
+    //create FrameIMU
+    ts = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+    state_vec = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentState();
+    FrameIMUPtr last_frame = std::make_shared<FrameIMU>(KEY_FRAME, ts, state_vec);
+    wolf_problem_ptr_->getTrajectoryPtr()->addFrame(last_frame);
+
+        //create a feature
+    delta_preint_cov = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentDeltaPreintCov();
+    delta_preint = wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_;
+    std::shared_ptr<FeatureIMU> feat_imu = std::make_shared<FeatureIMU>(delta_preint, delta_preint_cov);
+    feat_imu->setCapturePtr(imu_ptr);
+
+        //create a constraintIMU
+    ConstraintIMUPtr constraint_imu = std::make_shared<ConstraintIMU>(feat_imu, last_frame);
+    feat_imu->addConstraint(constraint_imu);
+    last_frame->addConstrainedBy(constraint_imu);
+
+    FrameIMUPtr ref_frame_ptr(std::static_pointer_cast<FrameIMU>(imu_ptr->getFramePtr()));
+
+    Eigen::Matrix<wolf::Scalar, 10, 1> expect;
+    Eigen::Vector3s ref_frame_p = ref_frame_ptr->getPPtr()->getVector();
+    Eigen::Quaternions ref_frame_o(ref_frame_ptr->getOPtr()->getVector().data());
+    Eigen::Vector3s ref_frame_v = ref_frame_ptr->getVPtr()->getVector();
+    Eigen::Vector3s current_frame_p = last_frame->getPPtr()->getVector();
+    Eigen::Quaternions current_frame_o(last_frame->getOPtr()->getVector().data());
+    Eigen::Vector3s current_frame_v = last_frame->getVPtr()->getVector();
+    Eigen::Vector3s acc_bias(ref_frame_ptr->getAccBiasPtr()->getVector()), gyro_bias(ref_frame_ptr->getGyroBiasPtr()->getVector());
+    Eigen::Matrix<wolf::Scalar, 9, 1> residu;
+    residu << 0,0,0,  0,0,0,  0,0,0;
+    
+    constraint_imu->expectation(ref_frame_p, ref_frame_o, ref_frame_v, acc_bias, gyro_bias, current_frame_p, current_frame_o, current_frame_v, expect);
+    std::cout << "expectation : " << expect.transpose() << std::endl;
+
+    constraint_imu->getResiduals(ref_frame_p, ref_frame_o, ref_frame_v, acc_bias, gyro_bias, current_frame_p, current_frame_o, current_frame_v,residu);
+    std::cout << "residuals : " << residu.transpose() << std::endl;
+
+    //reset origin of motion to new frame
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(last_frame);
+    imu_ptr->setFramePtr(last_frame);
+    }
+    /// ******************************************************************************************** ///
+
+    mpu_clock = 0.002135;
+    //data_ << 0.581990, -0.191602, 10.071057, 0.136836, 0.203912, -0.057686;
+	data_ << 0.0, 0.0, 9.81, 0.0, 0.0, 0.0;
+    t.set(mpu_clock);
+    imu_ptr->setData(data_);
+    imu_ptr->setTimeStamp(t);
+    sensor_ptr->process(imu_ptr);
+
+    mpu_clock = 0.003040;
+    //data_ << 0.596360, -0.225132, 10.205178, 0.154276, 0.174399, -0.036221;
+    data_ << 0.0, 0.0, 9.81, 0.0, 0.0, 0.0;
+    t.set(mpu_clock);
+    imu_ptr->setData(data_);
+    imu_ptr->setTimeStamp(t);
+    sensor_ptr->process(imu_ptr);
+
+    if(c1){
+    /// ******************************************************************************************** ///
+    /// constraint creation
+    //create FrameIMU
+    ts = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+    state_vec = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentState();
+    FrameIMUPtr last_frame = std::make_shared<FrameIMU>(KEY_FRAME, ts, state_vec);
+    wolf_problem_ptr_->getTrajectoryPtr()->addFrame(last_frame);
+
+        //create a feature
+    delta_preint_cov = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentDeltaPreintCov();
+    delta_preint = wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_;
+    std::shared_ptr<FeatureIMU> feat_imu = std::make_shared<FeatureIMU>(delta_preint, delta_preint_cov);
+    feat_imu->setCapturePtr(imu_ptr);
+
+        //create a constraintIMU
+    ConstraintIMUPtr constraint_imu = std::make_shared<ConstraintIMU>(feat_imu, last_frame);
+    feat_imu->addConstraint(constraint_imu);
+    last_frame->addConstrainedBy(constraint_imu);
+
+    FrameIMUPtr ref_frame_ptr(std::static_pointer_cast<FrameIMU>(imu_ptr->getFramePtr()));
+
+    Eigen::Matrix<wolf::Scalar, 10, 1> expect;
+    Eigen::Vector3s ref_frame_p = ref_frame_ptr->getPPtr()->getVector();
+    Eigen::Quaternions ref_frame_o(ref_frame_ptr->getOPtr()->getVector().data());
+    Eigen::Vector3s ref_frame_v = ref_frame_ptr->getVPtr()->getVector();
+    Eigen::Vector3s current_frame_p = last_frame->getPPtr()->getVector();
+    Eigen::Quaternions current_frame_o(last_frame->getOPtr()->getVector().data());
+    Eigen::Vector3s current_frame_v = last_frame->getVPtr()->getVector();
+    Eigen::Vector3s acc_bias(ref_frame_ptr->getAccBiasPtr()->getVector()), gyro_bias(ref_frame_ptr->getGyroBiasPtr()->getVector());
+    Eigen::Matrix<wolf::Scalar, 9, 1> residu;
+    residu << 0,0,0,  0,0,0,  0,0,0;
+    
+    constraint_imu->expectation(ref_frame_p, ref_frame_o, ref_frame_v, acc_bias, gyro_bias, current_frame_p, current_frame_o, current_frame_v, expect);
+    std::cout << "expectation : " << expect.transpose() << std::endl;
+
+    constraint_imu->getResiduals(ref_frame_p, ref_frame_o, ref_frame_v, acc_bias, gyro_bias, current_frame_p, current_frame_o, current_frame_v,residu);
+    std::cout << "residuals : " << residu.transpose() << std::endl;
+
+    //reset origin of motion to new frame
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(last_frame);
+    imu_ptr->setFramePtr(last_frame);
+    }
+
+    mpu_clock = 0.004046;
+    //data_ << 0.553250, -0.203577, 10.324929, 0.128787, 0.156959, -0.044270;
+    data_ << 0.0, 0.0, 9.81, 0.0, 0.0, 0.0;
+    t.set(mpu_clock);
+    imu_ptr->setData(data_);
+    imu_ptr->setTimeStamp(t);
+    sensor_ptr->process(imu_ptr);
+
+    mpu_clock = 0.005045;
+    //data_ << 0.548459, -0.184417, 10.387200, 0.083175, 0.120738, -0.026831;
+    data_ << 0.0, 0.0, 9.81, 0.0, 0.0, 0.0;
+    t.set(mpu_clock);
+    imu_ptr->setData(data_);
+    imu_ptr->setTimeStamp(t);
+    sensor_ptr->process(imu_ptr);
+
+    //create the constraint
+        //create FrameIMU
+    ts = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+    state_vec = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentState();
+    FrameIMUPtr last_frame = std::make_shared<FrameIMU>(KEY_FRAME, ts, state_vec);
+    wolf_problem_ptr_->getTrajectoryPtr()->addFrame(last_frame);
+
+        //create a feature
+    delta_preint_cov = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentDeltaPreintCov();
+    delta_preint = wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_;
+    std::shared_ptr<FeatureIMU> feat_imu = std::make_shared<FeatureIMU>(delta_preint, delta_preint_cov);
+    feat_imu->setCapturePtr(imu_ptr);
+
+        //create a constraintIMU
+    ConstraintIMUPtr constraint_imu = std::make_shared<ConstraintIMU>(feat_imu, last_frame);
+    feat_imu->addConstraint(constraint_imu);
+    last_frame->addConstrainedBy(constraint_imu);
+
+    FrameIMUPtr ref_frame_ptr(std::static_pointer_cast<FrameIMU>(imu_ptr->getFramePtr()));
+
+    Eigen::Matrix<wolf::Scalar, 10, 1> expect;
+    Eigen::Vector3s ref_frame_p = ref_frame_ptr->getPPtr()->getVector();
+    Eigen::Quaternions ref_frame_o(ref_frame_ptr->getOPtr()->getVector().data());
+    Eigen::Vector3s ref_frame_v = ref_frame_ptr->getVPtr()->getVector();
+    Eigen::Vector3s current_frame_p = last_frame->getPPtr()->getVector();
+    Eigen::Quaternions current_frame_o(last_frame->getOPtr()->getVector().data());
+    Eigen::Vector3s current_frame_v = last_frame->getVPtr()->getVector();
+    Eigen::Vector3s acc_bias(ref_frame_ptr->getAccBiasPtr()->getVector()), gyro_bias(ref_frame_ptr->getGyroBiasPtr()->getVector());
+    Eigen::Matrix<wolf::Scalar, 9, 1> residu;
+    residu << 0,0,0,  0,0,0,  0,0,0;
+    
+    constraint_imu->expectation(ref_frame_p, ref_frame_o, ref_frame_v, acc_bias, gyro_bias, current_frame_p, current_frame_o, current_frame_v, expect);
+    std::cout << "expectation : " << expect.transpose() << std::endl;
+
+    constraint_imu->getResiduals(ref_frame_p, ref_frame_o, ref_frame_v, acc_bias, gyro_bias, current_frame_p, current_frame_o, current_frame_v,residu);
+    std::cout << "residuals : " << residu.transpose() << std::endl;
+
+    if(wolf_problem_ptr_->check(1)){
+        wolf_problem_ptr_->print(4,1,1,1);
+    }
+
+
+    ///having a look at covariances
+    Eigen::MatrixXs predelta_cov;
+    predelta_cov.resize(9,9);
+    predelta_cov = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentDeltaPreintCov();
+    //std::cout << "predelta_cov : \n" << predelta_cov << std::endl; 
+
+        ///Optimization
+    // PRIOR
+    //FrameBasePtr first_frame = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front();
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    //SensorBasePtr sensorbase = std::make_shared<SensorBase>("ABSOLUTE POSE", nullptr, nullptr, nullptr, 0);
+    //CaptureFixPtr initial_covariance = std::make_shared<CaptureFix>(TimeStamp(0), sensorbase, first_frame->getState().head(7), Eigen::Matrix6s::Identity() * 0.01);
+    //first_frame->addCapture(initial_covariance);
+    //initial_covariance->process();
+    //std::cout << "initial covariance: constraint " << initial_covariance->getFeatureList().front()->getConstrainedByList().front()->id() << std::endl << initial_covariance->getFeatureList().front()->getMeasurementCovariance() << std::endl;
+
+    // COMPUTE COVARIANCES
+    std::cout << "computing covariances..." << std::endl;
+    ceres_manager_wolf_diff->computeCovariances(ALL_MARGINALS);//ALL_MARGINALS, ALL
+    std::cout << "computed!" << std::endl;
+
+    /*
+    // SOLVING PROBLEMS
+    ceres::Solver::Summary summary_diff;
+    std::cout << "solving..." << std::endl;
+    Eigen::VectorXs prev_wolf_state = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getState();
+    summary_diff = ceres_manager_wolf_diff->solve();
+    Eigen::VectorXs post_wolf_state = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getState();
+    std::cout << " prev_wolf_state : " << prev_wolf_state.transpose() << "\n post_wolf_state : " << post_wolf_state.transpose() << std::endl;
+    //std::cout << summary_wolf_diff.BriefReport() << std::endl;
+    std::cout << "solved!" << std::endl;
+    */
+
+    /*
+    std::cout << "WOLF AUTO DIFF" << std::endl;
+    std::cout << "Jacobian evaluation: " << summary_wolf.jacobian_evaluation_time_in_seconds << std::endl;
+    std::cout << "Total time: " << summary_wolf.total_time_in_seconds << std::endl;
+    */
+
+    return 0;
+}
\ No newline at end of file
diff --git a/src/examples/test_image.cpp b/src/examples/test_image.cpp
index 27e893067928f833488e80a4edf917912e274038..e79354c92eb1a51b38692985f03986ef4dc688ff 100644
--- a/src/examples/test_image.cpp
+++ b/src/examples/test_image.cpp
@@ -193,9 +193,9 @@ int main(int argc, char** argv)
 
 
 //            std::cout << "Last key frame pose: "
-//                      << wolf_problem_ptr_->getLastKeyFramePtr()->getPPtr()->getVector().transpose() << std::endl;
+//                      << wolf_problem_ptr_->getLastKeyFramePtr()->getPPtr()->getState().transpose() << std::endl;
 //            std::cout << "Last key frame orientation: "
-//                      << wolf_problem_ptr_->getLastKeyFramePtr()->getOPtr()->getVector().transpose() << std::endl;
+//                      << wolf_problem_ptr_->getLastKeyFramePtr()->getOPtr()->getState().transpose() << std::endl;
 
 //            cv::waitKey(0);
 //        }
diff --git a/src/examples/test_imuDock.cpp b/src/examples/test_imuDock.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..17d39a10c1d3544c5b317bab83827d41b2281837
--- /dev/null
+++ b/src/examples/test_imuDock.cpp
@@ -0,0 +1,318 @@
+/**
+ * \file test_imuDock.cpp
+ *
+ *  Created on: July 18, 2017
+ *      \author: Dinesh Atchuthan
+ */
+
+#include "wolf.h"
+#include "problem.h"
+#include "ceres_wrapper/ceres_manager.h"
+#include "sensor_imu.h"
+#include "processor_imu.h"
+#include "sensor_odom_3D.h"
+#include "processor_odom_3D.h"
+
+//Constraints headers
+#include "constraint_fix_3D.h"
+#include "constraint_fix_bias.h"
+
+//std
+#include <iostream>
+#include <fstream>
+
+#define OUTPUT_RESULTS
+//#define ADD_KF3
+
+/*                              OFFLINE VERSION
+    In this test, we use the experimental conditions needed for Humanoids 2017.
+    IMU data are acquired using the docking station. 
+
+    Constraints are (supposing to KeyFrames, stateblocks or first Keyframe are noted *1 and second Keyframes's are *2) :
+    invar       : P1, V1, V2
+    var         : Q1,B1,P2,Q2,B2
+    constraints : Odometry constraint between KeyFrames
+                  IMU constraint
+                  FixBias constraint --> makes the problem observable (adding a big covariance on all part but a smaller one on yaw)
+                  Fix3D constraint
+
+    What we expect  : Estimate biases (this will strongly depend on the actual trajectory of the IMU)
+                      Estimate the position and orienttion of the IMU (check with the standard deviation using covariance matrix)
+
+    Representation of the application:
+
+                                    Imu
+                        KF1----------â—¼----------KF2
+                   /----P1----------\ /----------P2             invar       : P1, V1, V2
+        Abs|------â—¼                 â—¼                          var         : Q1,B1,P2,Q2,B2
+                   \----Q1----------/ \----------Q2
+                        V1          Odom
+        Abs|------â—¼-----B1
+*/
+int main(int argc, char** argv)
+{
+    //#################################################### INITIALIZATION
+    using namespace wolf;
+
+    //___get input file for imu data___
+    std::ifstream imu_data_input;
+    const char * filename_imu;
+    if (argc < 02)
+    {
+        WOLF_ERROR("Missing 1 input argument (path to imu data file).")
+        return 1; //return with error
+    }
+    else
+    {
+        filename_imu = argv[1];
+
+        imu_data_input.open(filename_imu);
+        WOLF_INFO("imu file : ", filename_imu)
+    }
+
+    // ___Check if the file is correctly opened___
+    if(!imu_data_input.is_open()){
+        WOLF_ERROR("Failed to open data file ! Exiting")
+        return 1;
+    }
+
+    #ifdef OUTPUT_RESULTS
+        //define output file
+        std::ofstream output_results_before, output_results_after, checking;
+        output_results_before.open("imu_dock_beforeOptim.dat");
+        output_results_after.open("imu_dock_afterOptim.dat");
+        checking.open("KF_pose_stdev.dat");
+    #endif
+
+    // ___initialize variabes that will be used through the code___
+    Eigen::VectorXs problem_origin(16);
+    Eigen::Vector7s imu_pose((Eigen::Vector7s()<<0,0,0,0,0,0,1).finished()), odom_pose((Eigen::Vector7s()<<0,0,0,0,0,0,1).finished());
+    problem_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+    
+    //Create vectors to store data and time
+    Eigen::Vector6s data_imu, data_odom;
+    Scalar clock;
+    TimeStamp ts(0), ts_output(0); //will be used to store the data timestamps and set timestamps in captures
+
+    // ___Define expected values___
+    Eigen::Vector7s expected_KF1_pose((Eigen::Vector7s()<<0,0,0,0,0,0,1).finished()), expected_KF2_pose((Eigen::Vector7s()<<0,-0.06,0,0,0,0,11).finished());
+
+    //#################################################### SETTING PROBLEM
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // ___Create the WOLF Problem + define origin of the problem___
+    ProblemPtr problem = Problem::create("PQVBB 3D");
+    CeresManager* ceres_manager = new CeresManager(problem);
+ 
+    // ___Configure Ceres if needed___
+
+    // ___Create sensors + processors___
+    SensorIMUPtr sensorIMU = std::static_pointer_cast<SensorIMU>(problem->installSensor("IMU", "Main IMU", imu_pose, wolf_root + "/src/examples/sensor_imu.yaml"));
+    ProcessorIMUPtr processorIMU = std::static_pointer_cast<ProcessorIMU>(problem->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu.yaml"));
+    
+    SensorOdom3DPtr sensorOdom = std::static_pointer_cast<SensorOdom3D>(problem->installSensor("ODOM 3D", "odom", odom_pose, wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml"));
+    ProcessorOdom3DPtr processorOdom = std::static_pointer_cast<ProcessorOdom3D>(problem->installProcessor("ODOM 3D", "odom", "odom", wolf_root + "/src/examples/processor_odom_3D.yaml"));
+    
+    // ___set origin of processors to the problem's origin___
+    FrameIMUPtr KF1 = std::static_pointer_cast<FrameIMU>(processorIMU->setOrigin(problem_origin, ts)); // XXX JS: setting ts to zero, and then reading clock from data, is inconsistent.
+    processorOdom->setOrigin(KF1);
+
+    //#################################################### PROCESS DATA
+    // ___process IMU and odometry___
+
+    //Create captures
+    CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sensorIMU, data_imu); //ts is set at 0
+    CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sensorOdom, data_odom, 6, 7, 6, 0);
+
+    //while we do not reach the end of file, read IMU input (ts, Ax, Ay, Az, Wx, Wy, Wz) and process data through capture
+    while(!imu_data_input.eof())
+    {
+        //read
+        imu_data_input >> clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5];
+
+        //set capture
+        ts.set(clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        //process
+        sensorIMU->process(imu_ptr);
+    }
+
+    //All IMU data have been processed, close the file
+    imu_data_input.close();
+
+    //A KeyFrame should have been created (depending on time_span in processors). get the last KeyFrame
+    // XXX JS: in my  opinion, we should control the KF creation better, not using time span. Is it possible?
+    #ifdef ADD_KF3
+        //Add a KeyFrame just before the motion actually starts (we did not move yet)
+        data_odom << 0,0,0, 0,0,0;
+        TimeStamp t_middle(0.307585);
+        mot_ptr->setTimeStamp(t_middle);
+        mot_ptr->setData(data_odom);
+        sensorOdom->process(mot_ptr);
+
+        //Also add a keyframe at the end of the motion
+        data_odom << 0,-0.06,0, 0,0,0;
+        ts.set(0.981573); //comment this if you want the last KF to be created at last imu's ts
+        mot_ptr->setTimeStamp(ts);
+        mot_ptr->setData(data_odom);
+        sensorOdom->process(mot_ptr);
+
+        FrameIMUPtr KF2 = std::static_pointer_cast<FrameIMU>(problem->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t_middle));
+        FrameIMUPtr KF3 = std::static_pointer_cast<FrameIMU>(problem->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    #else
+        //now impose final odometry using last timestamp of imu
+        data_odom << 0,-0.06,0, 0,0,0;
+        mot_ptr->setTimeStamp(ts);
+        mot_ptr->setData(data_odom);
+        sensorOdom->process(mot_ptr);
+
+        FrameIMUPtr KF2 = std::static_pointer_cast<FrameIMU>(problem->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    #endif
+
+    //#################################################### OPTIMIZATION PART
+    // ___Create needed constraints___
+
+    //Add Fix3D constraint on first KeyFrame (with large covariance except for yaw)
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6);
+    featureFix_cov.topLeftCorner(3,3) *= 1e-8; // position variances (it's fixed anyway)
+    featureFix_cov(3,3) = pow( .02  , 2); // roll variance
+    featureFix_cov(4,4) = pow( .02  , 2); // pitch variance
+    featureFix_cov(5,5) = pow( .01 , 2); // yaw variance
+    CaptureBasePtr cap_fix = KF1->addCapture(std::make_shared<CaptureMotion>(0, nullptr, problem_origin.head(7), 7, 7, 6, 0));
+    FeatureBasePtr featureFix = cap_fix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", problem_origin.head(7), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(featureFix->addConstraint(std::make_shared<ConstraintFix3D>(featureFix)));
+
+    Eigen::MatrixXs featureFixBias_cov(6,6);
+    featureFixBias_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFixBias_cov.topLeftCorner(3,3) *= sensorIMU->getAbInitialStdev() * sensorIMU->getAbInitialStdev();
+    featureFixBias_cov.bottomRightCorner(3,3) *= sensorIMU->getWbInitialStdev() * sensorIMU->getWbInitialStdev();
+    CaptureBasePtr cap_fixbias = KF1->addCapture(std::make_shared<CaptureMotion>(0, nullptr, problem_origin.tail(6), featureFixBias_cov, 6, 6, 6, 0));
+    //create a FeatureBase to constraint biases
+    FeatureBasePtr featureFixBias = cap_fixbias->addFeature(std::make_shared<FeatureBase>("FIX BIAS", problem_origin.tail(6), featureFixBias_cov));
+    ConstraintFixBiasPtr ctr_fixBias = std::static_pointer_cast<ConstraintFixBias>(featureFixBias->addConstraint(std::make_shared<ConstraintFixBias>(featureFixBias)));
+
+    // ___Fix/Unfix stateblocks___
+    KF1->getPPtr()->fix();
+    KF1->getOPtr()->unfix();
+    KF1->getVPtr()->fix();
+    KF1->getAccBiasPtr()->unfix();
+    KF1->getGyroBiasPtr()->unfix();
+
+    #ifdef ADD_KF3
+        KF2->getPPtr()->fix();
+        KF2->getOPtr()->unfix();
+        KF2->getVPtr()->fix();
+        KF2->getAccBiasPtr()->unfix();
+        KF2->getGyroBiasPtr()->unfix();
+
+        KF3->getPPtr()->unfix();
+        KF3->getOPtr()->unfix();
+        KF3->getVPtr()->fix();
+        KF3->getAccBiasPtr()->unfix();
+        KF3->getGyroBiasPtr()->unfix();
+    #else
+        KF2->getPPtr()->unfix();
+        KF2->getOPtr()->unfix();
+        KF2->getVPtr()->fix();
+        KF2->getAccBiasPtr()->unfix();
+        KF2->getGyroBiasPtr()->unfix();
+    #endif
+
+    #ifdef OUTPUT_RESULTS
+        // ___OUTPUT___
+        /* Produce output file for matlab visualization
+         * first output : estimated trajectory BEFORE optimization (getting the states each millisecond)
+         */
+
+        unsigned int time_iter(0);
+        Scalar ms(0.001);
+        ts_output.set(0);
+        while(ts_output.get() < ts.get() + ms)
+        {
+            output_results_before << ts_output.get() << "\t" << problem->getState(ts_output).transpose() << std::endl;
+            time_iter++;
+            ts_output.set(time_iter * ms);
+        }
+    #endif
+
+    // ___Solve + compute covariances___
+    problem->print(4,0,1,0);
+    std::string report = ceres_manager->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager->computeCovariances(ALL_MARGINALS);
+    problem->print(1,0,1,0);
+
+    //#################################################### RESULTS PART
+
+    // ___Get standard deviation from covariances___
+    #ifdef ADD_KF3
+        Eigen::MatrixXs cov_KF1(16,16), cov_KF2(16,16), cov_KF3(16,16);
+
+        problem->getFrameCovariance(KF1, cov_KF1);
+        problem->getFrameCovariance(KF2, cov_KF2);
+        problem->getFrameCovariance(KF3, cov_KF3);
+
+        Eigen::Matrix<wolf::Scalar, 16, 1> stdev_KF1, stdev_KF2, stdev_KF3;
+
+        stdev_KF1 = cov_KF1.diagonal().array().sqrt();
+        stdev_KF2 = cov_KF2.diagonal().array().sqrt();
+        stdev_KF3 = cov_KF3.diagonal().array().sqrt();
+
+        WOLF_DEBUG("stdev KF1 : ", stdev_KF1.transpose());
+        WOLF_DEBUG("stdev KF2 : ", stdev_KF2.transpose());
+        WOLF_DEBUG("stdev KF3 : ", stdev_KF3.transpose());
+    #else
+        Eigen::MatrixXs cov_KF1(16,16), cov_KF2(16,16);
+
+        problem->getFrameCovariance(KF1, cov_KF1);
+        problem->getFrameCovariance(KF2, cov_KF2);
+
+        Eigen::Matrix<wolf::Scalar, 16, 1> stdev_KF1, stdev_KF2;
+
+        stdev_KF1 = cov_KF1.diagonal().array().sqrt();
+        stdev_KF2 = cov_KF2.diagonal().array().sqrt();
+
+        WOLF_DEBUG("stdev KF1 : \n", stdev_KF1.transpose());
+        WOLF_DEBUG("stdev KF2 : \n", stdev_KF2.transpose());
+    #endif
+    
+
+    #ifdef OUTPUT_RESULTS
+        // ___OUTPUT___
+        /* Produce output file for matlab visualization
+         * Second output:   KF2 position standard deviation computed
+         *                  estimated trajectory AFTER optimization 
+         *                  + get KF2 timestamp + state just in case the loop is not working as expected
+         */
+
+        //estimated trajectort
+        time_iter = 0;
+        ts_output.set(0);
+        while(ts_output.get() < ts.get() + ms)
+        {
+            output_results_after << ts_output.get() << "\t" << problem->getState(ts_output).transpose() << std::endl;
+            time_iter++;
+            ts_output.set(time_iter * ms);
+        }
+
+        //finally, output the timestamp, state and stdev associated to KFs
+        #ifdef ADD_KF3
+            checking << KF2->getTimeStamp().get() << "\t" << KF2->getState().transpose() << "\t" << stdev_KF2.transpose() << std::endl;
+            checking << KF3->getTimeStamp().get() << "\t" << KF3->getState().transpose() << "\t" << stdev_KF3.transpose() << std::endl;
+        #else
+            checking << KF2->getTimeStamp().get() << "\t" << KF2->getState().transpose() << "\t" << stdev_KF2.transpose() << std::endl;
+        #endif
+    #endif
+    
+    // ___Are expected values in the range of estimated +/- 2*stdev ?___
+
+    #ifdef OUTPUT_RESULTS
+        output_results_before.close();
+        output_results_after.close();
+        checking.close();
+    #endif
+
+    return 0;
+}
diff --git a/src/examples/test_imuDock_autoKFs.cpp b/src/examples/test_imuDock_autoKFs.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..2f4b67fd8046e1950801ddd24bb10457e338ece6
--- /dev/null
+++ b/src/examples/test_imuDock_autoKFs.cpp
@@ -0,0 +1,311 @@
+/**
+ * \file test_imuDock_autoKFs.cpp
+ *
+ *  Created on: July 22, 2017
+ *      \author: Dinesh Atchuthan
+ */
+
+#include "wolf.h"
+#include "problem.h"
+#include "ceres_wrapper/ceres_manager.h"
+#include "sensor_imu.h"
+#include "processor_imu.h"
+#include "sensor_odom_3D.h"
+#include "processor_odom_3D.h"
+
+//Constraints headers
+#include "constraint_fix_3D.h"
+#include "constraint_fix_bias.h"
+
+//std
+#include <iostream>
+#include <fstream>
+
+#define OUTPUT_RESULTS
+//#define AUTO_KFS
+
+/*                              OFFLINE VERSION
+    In this test, we use the experimental conditions needed for Humanoids 2017.
+    IMU data are acquired using the docking station. 
+
+    Constraints are (supposing to KeyFrames, stateblocks or first Keyframe are noted *1 and second Keyframes's are *2) :
+    invar       : P1, V1, V2
+    var         : Q1,B1,P2,Q2,B2
+
+    All Keyframes coming after KF2 are constrained just like KF2
+    constraints : Odometry constraint between KeyFrames
+                  IMU constraint
+                  FixBias constraint --> makes the problem observable (adding a big covariance on all part but a smaller one on yaw)
+                  Fix3D constraint
+
+    What we expect  : Estimate biases (this will strongly depend on the actual trajectory of the IMU)
+                      Estimate the position and orienttion of the IMU (check with the standard deviation using covariance matrix)
+
+    Representation of the application:
+
+                                    Imu
+                        KF1----------â—¼----------KF2--..
+                   /----P1----------\ /----------P2--..             invar       : P1, V1, V2
+        Abs|------â—¼                 â—¼                          var         : Q1,B1,P2,Q2,B2
+                   \----Q1----------/ \----------Q2--..
+                        V1          Odom         v2  ..
+        Abs|------â—¼-----B1                       B2  ..
+*/
+int main(int argc, char** argv)
+{
+    //#################################################### INITIALIZATION
+    using namespace wolf;
+
+    //___get input files for imu and odom data___
+    std::ifstream imu_data_input, odom_data_input;
+    const char * filename_imu;
+    const char * filename_odom;
+    if (argc < 03)
+    {
+        WOLF_ERROR("Missing input argument : path to imu or/and odom data file(s).")
+        return 1; //return with error
+    }
+    else
+    {
+        filename_imu = argv[1];
+        filename_odom = argv[2];
+
+        imu_data_input.open(filename_imu);
+        WOLF_INFO("imu file : ", filename_imu)
+        odom_data_input.open(filename_odom);
+        WOLF_INFO("odom file : ", filename_odom)
+    }
+
+    // ___Check if the file is correctly opened___
+    if(!imu_data_input.is_open() || !odom_data_input.is_open()){
+        WOLF_ERROR("Failed to open data file ! Exiting")
+        return 1;
+    }
+
+    #ifdef OUTPUT_RESULTS
+        //define output file
+        std::ofstream output_results_before, output_results_after, checking;
+        output_results_before.open("imu_dock_beforeOptim.dat");
+        output_results_after.open("imu_dock_afterOptim.dat");
+        checking.open("KF_pose_stdev.dat");
+    #endif
+
+    // ___initialize variabes that will be used through the code___
+    Eigen::VectorXs problem_origin(16);
+    Eigen::Vector7s imu_pose((Eigen::Vector7s()<<0,0,0,0,0,0,1).finished()), odom_pose((Eigen::Vector7s()<<0,0,0,0,0,0,1).finished());
+    problem_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+    
+    //Create vectors to store data and time
+    Eigen::Vector6s data_imu, data_odom;
+    Scalar clock;
+    TimeStamp ts(0), ts_output(0); //will be used to store the data timestamps and set timestamps in captures
+
+    // ___Define expected values___
+    Eigen::Vector7s expected_KF1_pose((Eigen::Vector7s()<<0,0,0,0,0,0,1).finished()), expected_KF2_pose((Eigen::Vector7s()<<0,-0.06,0,0,0,0,11).finished());
+
+    #ifdef AUTO_KFs
+        std::array<Scalar, 50> lastms_imuData;
+    #endif
+    //#################################################### SETTING PROBLEM
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // ___Create the WOLF Problem + define origin of the problem___
+    ProblemPtr problem = Problem::create("PQVBB 3D");
+    CeresManager* ceres_manager = new CeresManager(problem);
+ 
+    // ___Configure Ceres if needed___
+
+    // ___Create sensors + processors___
+    SensorIMUPtr sensorIMU = std::static_pointer_cast<SensorIMU>(problem->installSensor("IMU", "Main IMU", imu_pose, wolf_root + "/src/examples/sensor_imu.yaml"));
+    ProcessorIMUPtr processorIMU = std::static_pointer_cast<ProcessorIMU>(problem->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu.yaml"));
+    
+    SensorOdom3DPtr sensorOdom = std::static_pointer_cast<SensorOdom3D>(problem->installSensor("ODOM 3D", "odom", odom_pose, wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml"));
+    ProcessorOdom3DPtr processorOdom = std::static_pointer_cast<ProcessorOdom3D>(problem->installProcessor("ODOM 3D", "odom", "odom", wolf_root + "/src/examples/processor_odom_3D.yaml"));
+    
+    // ___set origin of processors to the problem's origin___
+    FrameIMUPtr KF1 = std::static_pointer_cast<FrameIMU>(processorIMU->setOrigin(problem_origin, ts)); // XXX JS: setting ts to zero, and then reading clock from data, is inconsistent.
+    processorOdom->setOrigin(KF1);
+
+    //#################################################### PROCESS DATA
+    // ___process IMU and odometry___
+
+    //Create captures
+    CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sensorIMU, data_imu); //ts is set at 0
+    CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sensorOdom, data_odom, 6, 7, 6, 0);
+
+    //while we do not reach the end of file, read IMU input (ts, Ax, Ay, Az, Wx, Wy, Wz) and process data through capture
+    while(!imu_data_input.eof())
+    {
+        //read
+        imu_data_input >> clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5];
+
+        //set capture
+        ts.set(clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        //process
+        sensorIMU->process(imu_ptr);
+    }
+
+    //Process all the odom data
+    // XXX JS: in my  opinion, we should control the KF creation better, not using time span. Is it possible?
+    while(!odom_data_input.eof())
+    {
+        //read
+        odom_data_input >> clock >> data_odom[0] >> data_odom[1] >> data_odom[2] >> data_odom[3] >> data_odom[4] >> data_odom[5];
+
+        //set capture
+        ts.set(clock);
+        mot_ptr->setTimeStamp(ts);
+        mot_ptr->setData(data_odom);
+
+        #ifdef AUTO_KFS
+            /* We want the KFs to be generated automatically but not using time span as argument of this generation
+             * For our application, w want the KFs to be generated when an odometry data is given under condition that the IMU is not moving
+             * We check wether the IMU is moving or not by computing the current stdev of the IMU based on data received during 50ms before the odom timestamp
+             * We compare this value to the stdev (noise) of the sensor (see sensor_imu.yaml)
+             * If the current stdev is below a threshold then we process the odometry data !
+             */
+
+             // TODO : get data to compute stdev with directly from the capture
+             //         -> see how these data are stored and change getIMUStdev(..) function defined below main() in this file
+             //         -> then just use the function to get this stdev of corresponding data
+
+        #else
+            //process anyway. KFs will be generated based on the configuration given in processor_odom_3D.yaml
+            sensorOdom->process(mot_ptr);
+        #endif
+    }
+
+    //All data have been processed, close the files
+    imu_data_input.close();
+    odom_data_input.close();
+    
+    //A KeyFrame should have been created (depending on time_span in processors). get all frames
+    FrameBaseList trajectory = problem->getTrajectoryPtr()->getFrameList();
+    
+
+    //#################################################### OPTIMIZATION PART
+    // ___Create needed constraints___
+
+    //Add Fix3D constraint on first KeyFrame (with large covariance except for yaw)
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6);
+    featureFix_cov.topLeftCorner(3,3) *= 1e-8; // position variances (it's fixed anyway)
+    featureFix_cov(3,3) = pow( .01  , 2); // roll variance
+    featureFix_cov(4,4) = pow( .01  , 2); // pitch variance
+    featureFix_cov(5,5) = pow( .001 , 2); // yaw variance
+    CaptureBasePtr cap_fix = KF1->addCapture(std::make_shared<CaptureMotion>(0, nullptr, problem_origin.head(7), 7, 7, 6, 0));
+    FeatureBasePtr featureFix = cap_fix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", problem_origin.head(7), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(featureFix->addConstraint(std::make_shared<ConstraintFix3D>(featureFix)));
+
+    Eigen::MatrixXs featureFixBias_cov(6,6);
+    featureFixBias_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFixBias_cov.topLeftCorner(3,3) *= sensorIMU->getAbInitialStdev() * sensorIMU->getAbInitialStdev();
+    featureFixBias_cov.bottomRightCorner(3,3) *= sensorIMU->getWbInitialStdev() * sensorIMU->getWbInitialStdev();
+    CaptureBasePtr cap_fixbias = KF1->addCapture(std::make_shared<CaptureMotion>(0, nullptr, problem_origin.tail(6), featureFixBias_cov, 6, 6, 6, 0));
+    //create a FeatureBase to constraint biases
+    FeatureBasePtr featureFixBias = cap_fixbias->addFeature(std::make_shared<FeatureBase>("FIX BIAS", problem_origin.tail(6), featureFixBias_cov));
+    ConstraintFixBiasPtr ctr_fixBias = std::static_pointer_cast<ConstraintFixBias>(featureFixBias->addConstraint(std::make_shared<ConstraintFixBias>(featureFixBias)));
+
+    // ___Fix/Unfix stateblocks___
+    // fix all Keyframes here
+
+    FrameIMUPtr frame_imu;
+    for(auto frame : trajectory)
+    {   
+        frame_imu = std::static_pointer_cast<FrameIMU>(frame);
+        if(frame_imu->isKey())
+        {
+            frame_imu->getPPtr()->fix();
+            frame_imu->getOPtr()->unfix();
+            frame_imu->getVPtr()->setState((Eigen::Vector3s()<<0,0,0).finished()); //fix all velocties to 0 ()
+            frame_imu->getVPtr()->fix();
+            frame_imu->getAccBiasPtr()->unfix();
+            frame_imu->getGyroBiasPtr()->unfix();
+        }
+    }
+    
+    //KF1 (origin) needs to be also fixed in position
+    KF1->getPPtr()->fix();
+
+    #ifdef OUTPUT_RESULTS
+        // ___OUTPUT___
+        /* Produce output file for matlab visualization
+         * first output : estimated trajectory BEFORE optimization (getting the states each millisecond)
+         */
+
+        unsigned int time_iter(0);
+        Scalar ms(0.001);
+        ts_output.set(0);
+        while(ts_output.get() < ts.get() + ms)
+        {
+            output_results_before << ts_output.get() << "\t" << problem->getState(ts_output).transpose() << std::endl;
+            time_iter++;
+            ts_output.set(time_iter * ms);
+        }
+    #endif
+
+    // ___Solve + compute covariances___
+    problem->print(4,0,1,0);
+    std::string report = ceres_manager->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager->computeCovariances(ALL_MARGINALS);
+    problem->print(1,0,1,0);
+
+    //#################################################### RESULTS PART
+
+    // ___Get standard deviation from covariances___ and output this in a file
+    Eigen::MatrixXs cov_KF(16,16);
+    Eigen::Matrix<wolf::Scalar, 16, 1> stdev_KF;
+    for(auto frame : trajectory)
+    {
+        if(frame->isKey())
+        {
+            problem->getFrameCovariance(frame, cov_KF);
+            stdev_KF = cov_KF.diagonal().array().sqrt();
+            #ifdef OUTPUT_RESULTS
+                checking << frame->getTimeStamp().get() << "\t" << frame->getState().transpose() << "\t" << stdev_KF.transpose() << std::endl;
+            #endif
+        }
+    }
+
+    #ifdef OUTPUT_RESULTS
+        // ___OUTPUT___
+        /* Produce output file for matlab visualization
+         * Second output:   KF position standard deviation computed
+         *                  estimated trajectory AFTER optimization 
+         */
+
+        //estimated trajectort
+        time_iter = 0;
+        ts_output.set(0);
+        while(ts_output.get() < ts.get() + ms)
+        {
+            output_results_after << ts_output.get() << "\t" << problem->getState(ts_output).transpose() << std::endl;
+            time_iter++;
+            ts_output.set(time_iter * ms);
+        }
+
+        //Finished writing in files : close them
+        output_results_before.close();
+        output_results_after.close();
+        checking.close();
+    #endif
+
+    return 0;
+}
+
+/*Scalar getIMUStdev(Eigen::VectorXs _data) //input argument : whatever will contain the data in the capture
+{
+    Eigen::Vector6s mean(Eigen::Vector6s::Zero()), stdev(Eigen::Vector6s::Zero());
+    unsigned int _data_size(_data.size());
+    
+    mean = _data.mean()/_data_size;
+
+    for (unsigned int i = 0; i < _data_size; i++)
+    {
+        stdev += pow(_data()-mean,2); //get the correct data from the container
+    }
+    return (stdev.array().sqrt()).maxCoeff();
+}*/
diff --git a/src/examples/test_imuPlateform_Offline.cpp b/src/examples/test_imuPlateform_Offline.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..40e556a43cc5be8561b555475aa957cb97324522
--- /dev/null
+++ b/src/examples/test_imuPlateform_Offline.cpp
@@ -0,0 +1,270 @@
+//Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "sensor_imu.h"
+#include "sensor_odom_3D.h"
+#include "capture_imu.h"
+#include "constraint_odom_3D.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu.h"
+#include "processor_odom_3D.h"
+#include "ceres_wrapper/ceres_manager.h"
+
+//std
+#include <iostream>
+#include <fstream>
+#include <iomanip>
+#include <ctime>
+#include <cmath>
+
+#define DEBUG_RESULTS
+
+int _kbhit();
+
+int main(int argc, char** argv)
+{
+    using namespace wolf;
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+
+    // LOADING DATA FILE (IMU)
+    // FOR IMU, file content is : Timestampt\t Ax\t Ay\t Az\t Wx\t Wy\t Wz
+    
+    std::ifstream imu_data_input;
+    const char * filename_imu;
+    if (argc < 02)
+    {
+        
+        WOLF_ERROR("Missing input argument! : needs 1 argument (path to imu data file).")
+        return 1;
+    }
+    else
+    {
+        filename_imu = argv[1];
+
+        imu_data_input.open(filename_imu);
+        WOLF_INFO("imu file : ", filename_imu)
+
+        //std::string dummy; //this is needed only if first line is headers or useless data
+        //getline(imu_data_input, dummy);
+    }
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        return 1;
+    }
+
+    #ifdef DEBUG_RESULTS
+    std::ofstream debug_results;
+    debug_results.open("debug_results_imu_constrained0.dat");
+    if(debug_results)
+        debug_results   << "%%TimeStamp\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t"
+                        << "Cov_X\t" << "Cov_Y\t" << "Cov_Z\t" << "Cov_Qx\t" << "Cov_Qy\t" << "Cov_Qz\t" << "Cov_Qw" << "Cov_Vx\t" << "Cov_Vy\t" << "Cov_Vz\t" << std::endl;
+    #endif
+
+    //===================================================== SETTING PROBLEM
+    std::string wolf_root = _WOLF_ROOT_DIR;
+        
+    // WOLF PROBLEM
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+    Eigen::VectorXs x_origin(16);
+    x_origin << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; //INITIAL CONDITIONS
+    TimeStamp t(0);
+
+    // CERES WRAPPER
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+
+    // SENSOR + PROCESSOR IMU
+    SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+    ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+    prc_imu_params->max_time_span = 10;
+    prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+    prc_imu_params->dist_traveled = 1000000000;
+    prc_imu_params->angle_turned = 1000000000;
+    
+    ProcessorBasePtr processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+    SensorIMUPtr sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+    ProcessorIMUPtr processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+    // SENSOR + PROCESSOR ODOM 3D
+    SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+    ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+    prc_odom3D_params->max_time_span = 1.9999;
+    prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+    prc_odom3D_params->dist_traveled = 1000000000;
+    prc_odom3D_params->angle_turned = 1000000000;
+
+    ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+    SensorOdom3DPtr sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+    ProcessorOdom3DPtr processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+    // reset origin of problem
+    t.set(0);
+    
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+    processor_ptr_odom3D->setOrigin(origin_KF);
+
+    //fix parts of the problem if needed
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6, 6, 0);
+
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+    t = ts;
+
+    clock_t begin = clock();
+    
+    while( !imu_data_input.eof())
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+    
+    TimeStamp t0, tf;
+    t0 = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().front().ts_;
+    tf = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+    int N = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().size();
+
+    //Finally, process the only one odom input
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    clock_t end = clock();
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    //closing file
+    imu_data_input.close();
+    //===================================================== END{PROCESS DATA}
+
+    double elapsed_secs = double(end - begin) / CLOCKS_PER_SEC;
+
+    // Final state
+    std::cout << "\nIntegration results ----------------------------------------------------------------------------------------------" << std::endl;
+    std::cout << "Initial    state: " << std::fixed << std::setprecision(3) << std::setw(8)
+    << x_origin.head(16).transpose() << std::endl;
+    std::cout << "Integrated delta: " << std::fixed << std::setprecision(3) << std::setw(8)
+    << wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_.transpose() << std::endl;
+    std::cout << "Integrated state: " << std::fixed << std::setprecision(3) << std::setw(8)
+    << wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentState().head(16).transpose() << std::endl;
+    std::cout << "Integrated std  : " << std::fixed << std::setprecision(3) << std::setw(8)
+    << (wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_cov_.diagonal().transpose()).array().sqrt() << std::endl;
+
+
+    // Print statistics
+    std::cout << "\nStatistics -----------------------------------------------------------------------------------" << std::endl;
+    std::cout << "If you want meaningful CPU metrics, remove all couts in the loop / remove DEBUG_RESULTS definition variable, and compile in RELEASE mode!" << std::endl;
+
+    /*TimeStamp t0, tf;
+    t0 = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().front().ts_;
+    tf = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+    int N = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().size();*/
+    std::cout << "t0        : " << t0.get() << " s" << std::endl;
+    std::cout << "tf        : " << tf.get() << " s" << std::endl;
+    std::cout << "duration  : " << tf-t0 << " s" << std::endl;
+    std::cout << "N samples : " << N << std::endl;
+    std::cout << "frequency : " << (N-1)/(tf-t0) << " Hz" << std::endl;
+    std::cout << "CPU time  : " << elapsed_secs << " s" << std::endl;
+    std::cout << "s/integr  : " << elapsed_secs/(N-1)*1e6 << " us" << std::endl;
+    std::cout << "integr/s  : " << (N-1)/elapsed_secs << " ips" << std::endl;
+
+    //fix parts of the problem if needed
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    
+    std::cout << "\t\t\t ______solving______" << std::endl;
+    std::string report = ceres_manager_wolf_diff->solve(2);// 0: nothing, 1: BriefReport, 2: FullReport
+    std::cout << report << std::endl;
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << "\t\t\t ______solved______" << std::endl;
+
+    wolf_problem_ptr_->print(4,1,1,1);
+
+    #ifdef DEBUG_RESULTS
+    Eigen::VectorXs frm_state(16);
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev;
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero());
+
+    wolf::FrameBaseList frame_list = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList();
+    for(FrameBasePtr frm_ptr : frame_list)
+    {
+        if(frm_ptr->isKey())
+        {   
+            //prepare needed variables
+            FrameIMUPtr frmIMU_ptr = std::static_pointer_cast<FrameIMU>(frm_ptr);
+            frm_state = frmIMU_ptr->getState();
+            ts = frmIMU_ptr->getTimeStamp();
+
+            //get data from covariance blocks
+            wolf_problem_ptr_->getFrameCovariance(frmIMU_ptr, covX);
+            wolf_problem_ptr_->getCovarianceBlock(frmIMU_ptr->getVPtr(), frmIMU_ptr->getVPtr(), cov3);
+            covX.block(7,7,3,3) = cov3;
+            wolf_problem_ptr_->getCovarianceBlock(frmIMU_ptr->getAccBiasPtr(), frmIMU_ptr->getAccBiasPtr(), cov3);
+            covX.block(10,10,3,3) = cov3;
+            wolf_problem_ptr_->getCovarianceBlock(frmIMU_ptr->getGyroBiasPtr(), frmIMU_ptr->getGyroBiasPtr(), cov3);
+            covX.block(13,13,3,3) = cov3;
+            for(int i = 0; i<16; i++)
+                cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+
+
+            debug_results << std::setprecision(16) << ts.get() << "\t" << frm_state(0) << "\t" << frm_state(1) << "\t" << frm_state(2)
+            << "\t" << frm_state(3) << "\t" << frm_state(4) << "\t" << frm_state(5) << "\t" << frm_state(6)
+            << "\t" << frm_state(7) << "\t" << frm_state(8) << "\t" << frm_state(9)
+            << "\t" << frm_state(10) << "\t" << frm_state(11) << "\t" << frm_state(12) << "\t" << frm_state(13) << "\t" << frm_state(14) << "\t" << frm_state(15)
+            << "\t" << cov_stdev(0) << "\t" << cov_stdev(1) << "\t" << cov_stdev(2)
+            << "\t" << cov_stdev(3) << "\t" << cov_stdev(4) << "\t" << cov_stdev(5) << "\t" << cov_stdev(6)
+            << "\t" << cov_stdev(7) << "\t" << cov_stdev(8) << "\t" << cov_stdev(9)
+            << "\t" << cov_stdev(10) << "\t" << cov_stdev(11) << "\t" << cov_stdev(12) << "\t" << cov_stdev(13) << "\t" << cov_stdev(14) << "\t" << cov_stdev(15) << std::endl;
+        }
+    }
+
+    debug_results.close();
+    WOLF_WARN("WARNING : DEBUG_RESULTS ACTIVATED - slows the process (writing results to result_debugs.dat file)")
+
+    #endif
+
+    return 0;
+
+}
+
+int _kbhit()
+{
+    struct timeval tv;
+    fd_set fds;
+    tv.tv_sec = 0;
+    tv.tv_usec = 0;
+    FD_ZERO(&fds);
+    FD_SET(STDIN_FILENO, &fds); //STDIN_FILENO is 0
+    select(STDIN_FILENO+1, &fds, NULL, NULL, &tv);
+    return FD_ISSET(STDIN_FILENO, &fds);
+}
diff --git a/src/examples/test_imu_constrained0.cpp b/src/examples/test_imu_constrained0.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a21d43563d4f9f954476b3ef18da1e6a4252b5cd
--- /dev/null
+++ b/src/examples/test_imu_constrained0.cpp
@@ -0,0 +1,380 @@
+//Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "sensor_imu.h"
+#include "sensor_odom_3D.h"
+#include "capture_imu.h"
+#include "constraint_odom_3D.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu.h"
+#include "processor_odom_3D.h"
+#include "ceres_wrapper/ceres_manager.h"
+
+//std
+#include <iostream>
+#include <fstream>
+#include <iomanip>
+#include <ctime>
+#include <cmath>
+
+#define DEBUG_RESULTS
+#define KF0_EVOLUTION
+
+int _kbhit();
+
+int main(int argc, char** argv)
+{
+    using namespace wolf;
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+
+    // LOADING DATA FILES (IMU + ODOM)
+    // FOR IMU, file content is : Timestampt\t Ax\t Ay\t Az\t Wx\t Wy\t Wz
+    // FOR ODOM, file content is : Timestampt\t Δpx\t  Δpy\t  Δpz\t  Δox\t  Δoy\t  Δoz
+    
+    
+    std::ifstream imu_data_input;
+    std::ifstream odom_data_input;
+    const char * filename_imu;
+    const char * filename_odom;
+    if (argc < 3)
+    {
+        std::cout << "Missing input argument! : needs 2 argument (path to imu and odom data files)." << std::endl;
+        return 1;
+    }
+    else
+    {
+        filename_imu = argv[1];
+        filename_odom = argv[2];
+
+        imu_data_input.open(filename_imu);
+        odom_data_input.open(filename_odom);
+
+        std::cout << "file imu : " << filename_imu <<"\t file odom : " << filename_odom << std::endl;
+
+        //std::string dummy; //this is needed only if first line is headers or useless data
+        //getline(imu_data_input, dummy);
+    }
+
+    if(!imu_data_input.is_open() || !odom_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        return 1;
+    }
+
+    #ifdef DEBUG_RESULTS
+    std::ofstream debug_results;
+    debug_results.open("debug_results_imu_constrained0.dat");
+    if(debug_results)
+        debug_results   << "%%TimeStamp\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t"
+                        << "Cov_X\t" << "Cov_Y\t" << "Cov_Z\t" << "Cov_Qx\t" << "Cov_Qy\t" << "Cov_Qz\t" << "Cov_Qw" << "Cov_Vx\t" << "Cov_Vy\t" << "Cov_Vz\t" << std::endl;
+    #endif
+
+    #ifdef KF0_EVOLUTION
+    std::ofstream KF0_evolution;
+    KF0_evolution.open("KF0_evolution.dat");
+    if(KF0_evolution)
+        KF0_evolution   << "%%TimeStamp\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t"
+                        << "Cov_X\t" << "Cov_Y\t" << "Cov_Z\t" << "Cov_Qx\t" << "Cov_Qy\t" << "Cov_Qz\t" << "Cov_Qw" << "Cov_Vx\t" << "Cov_Vy\t" << "Cov_Vz\t" << std::endl;
+    #endif
+
+    //===================================================== SETTING PROBLEM
+    std::string wolf_root = _WOLF_ROOT_DIR;
+        
+    // WOLF PROBLEM
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+    Eigen::VectorXs x_origin(16);
+    Eigen::Vector6s origin_bias;
+    x_origin << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; //INITIAL CONDITIONS    0.05,0.03,.00,  0.2,-0.05,.00;
+    TimeStamp t(0);
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+    imu_data_input >> origin_bias[0] >> origin_bias[1] >> origin_bias[2] >> origin_bias[3] >> origin_bias[4] >> origin_bias[5];
+
+    // CERES WRAPPER
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+
+    // SENSOR + PROCESSOR IMU
+    SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+    ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+    prc_imu_params->max_time_span = 10;
+    prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+    prc_imu_params->dist_traveled = 1000000000;
+    prc_imu_params->angle_turned = 1000000000;
+    
+    ProcessorBasePtr processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+    SensorIMUPtr sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+    ProcessorIMUPtr processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+    // SENSOR + PROCESSOR ODOM 3D
+    SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+    ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+    prc_odom3D_params->max_time_span = 20.9999;
+    prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+    prc_odom3D_params->dist_traveled = 1000000000;
+    prc_odom3D_params->angle_turned = 1000000000;
+
+    ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+    SensorOdom3DPtr sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+    ProcessorOdom3DPtr processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+    // reset origin of problem
+    t.set(0);
+    Eigen::Matrix<wolf::Scalar, 10, 1> expected_final_state;
+    
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+    processor_ptr_odom3D->setOrigin(origin_KF);
+
+    odom_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                            expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+
+    //fix parts of the problem if needed
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,0,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    TimeStamp t_odom(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6, 6, 0);
+    
+    //read first odom data from file
+    odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+    t_odom.set(input_clock);
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+    t = ts;
+
+    clock_t begin = clock();
+    
+    while( !imu_data_input.eof() && !odom_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+
+        if(ts.get() == t_odom.get())
+        {
+            // PROCESS ODOM 3D DATA
+            mot_ptr->setTimeStamp(t_odom);
+            mot_ptr->setData(data_odom3D);
+            sen_odom3D->process(mot_ptr);
+
+            //prepare next odometry measurement if there is any
+            odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+            t_odom.set(input_clock);
+        }
+
+        #ifdef KF0_EVOLUTION
+        
+        if( (ts.get() - t.get()) >= 0.05 )
+        {
+            t = ts;
+            //std::string report = ceres_manager_wolf_diff->solve(1); //0: nothing, 1: BriefReport, 2: FullReport
+        
+        
+            Eigen::VectorXs frm_state(16);
+            frm_state = origin_KF->getState();
+
+            KF0_evolution << std::setprecision(16) << ts.get() << "\t" << frm_state(0) << "\t" << frm_state(1) << "\t" << frm_state(2)
+                << "\t" << frm_state(3) << "\t" << frm_state(4) << "\t" << frm_state(5) << "\t" << frm_state(6)
+                << "\t" << frm_state(7) << "\t" << frm_state(8) << "\t" << frm_state(9)
+                << "\t" << frm_state(10) << "\t" << frm_state(11) << "\t" << frm_state(12) << "\t" << frm_state(13) << "\t" << frm_state(14) << "\t" << frm_state(15) << std::endl;
+        }
+
+        #endif
+    }
+
+    clock_t end = clock();
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    //closing file
+    imu_data_input.close();
+    odom_data_input.close();
+
+    #ifdef KF0_EVOLUTION
+    KF0_evolution.close();
+    #endif
+
+    //===================================================== END{PROCESS DATA}
+
+    double elapsed_secs = double(end - begin) / CLOCKS_PER_SEC;
+
+    // Final state
+    std::cout << "\nIntegration results ----------------------------------------------------------------------------------------------" << std::endl;
+    std::cout << "Initial    state: " << std::fixed << std::setprecision(3) << std::setw(8)
+    << x_origin.head(16).transpose() << std::endl;
+    std::cout << "Integrated delta: " << std::fixed << std::setprecision(3) << std::setw(8)
+    << wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_.transpose() << std::endl;
+    std::cout << "Integrated state: " << std::fixed << std::setprecision(3) << std::setw(8)
+    << wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentState().head(16).transpose() << std::endl;
+    std::cout << "Integrated std  : " << std::fixed << std::setprecision(3) << std::setw(8)
+    << (wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_cov_.diagonal()).array().sqrt() << std::endl;
+
+
+    // Print statistics
+    std::cout << "\nStatistics -----------------------------------------------------------------------------------" << std::endl;
+    std::cout << "If you want meaningful CPU metrics, remove all couts in the loop / remove DEBUG_RESULTS definition variable, and compile in RELEASE mode!" << std::endl;
+
+    TimeStamp t0, tf;
+    t0 = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().front().ts_;
+    tf = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+    int N = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().size();
+    std::cout << "t0        : " << t0.get() << " s" << std::endl;
+    std::cout << "tf        : " << tf.get() << " s" << std::endl;
+    std::cout << "duration  : " << tf-t0 << " s" << std::endl;
+    std::cout << "N samples : " << N << std::endl;
+    std::cout << "frequency : " << (N-1)/(tf-t0) << " Hz" << std::endl;
+    std::cout << "CPU time  : " << elapsed_secs << " s" << std::endl;
+    std::cout << "s/integr  : " << elapsed_secs/(N-1)*1e6 << " us" << std::endl;
+    std::cout << "integr/s  : " << (N-1)/elapsed_secs << " ips" << std::endl;
+
+    //fix parts of the problem if needed
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    
+    std::cout << "\t\t\t ______solving______" << std::endl;
+    std::string report = ceres_manager_wolf_diff->solve(2); //0: nothing, 1: BriefReport, 2: FullReport
+    std::cout << report << std::endl;
+
+    last_KF->getAccBiasPtr()->fix();
+    last_KF->getGyroBiasPtr()->fix();
+
+    std::cout << "\t\t\t solving after fixBias" << std::endl;
+    report = ceres_manager_wolf_diff->solve(1); //0: nothing, 1: BriefReport, 2: FullReport
+    std::cout << report << std::endl;
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << "\t\t\t ______solved______" << std::endl;
+
+    wolf_problem_ptr_->print(4,1,1,1);
+
+    #ifdef DEBUG_RESULTS
+    Eigen::VectorXs frm_state(16);
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev;
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero());
+
+    wolf::FrameBaseList frame_list = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList();
+    for(FrameBasePtr frm_ptr : frame_list)
+    {
+        if(frm_ptr->isKey())
+        {   
+            //prepare needed variables
+            FrameIMUPtr frmIMU_ptr = std::static_pointer_cast<FrameIMU>(frm_ptr);
+            frm_state = frmIMU_ptr->getState();
+            ts = frmIMU_ptr->getTimeStamp();
+
+            //get data from covariance blocks
+            wolf_problem_ptr_->getFrameCovariance(frmIMU_ptr, covX);
+            wolf_problem_ptr_->getCovarianceBlock(frmIMU_ptr->getVPtr(), frmIMU_ptr->getVPtr(), cov3);
+            covX.block(7,7,3,3) = cov3;
+            wolf_problem_ptr_->getCovarianceBlock(frmIMU_ptr->getAccBiasPtr(), frmIMU_ptr->getAccBiasPtr(), cov3);
+            covX.block(10,10,3,3) = cov3;
+            wolf_problem_ptr_->getCovarianceBlock(frmIMU_ptr->getGyroBiasPtr(), frmIMU_ptr->getGyroBiasPtr(), cov3);
+            covX.block(13,13,3,3) = cov3;
+            for(int i = 0; i<16; i++)
+                cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+
+
+            debug_results << std::setprecision(16) << ts.get() << "\t" << frm_state(0) << "\t" << frm_state(1) << "\t" << frm_state(2)
+            << "\t" << frm_state(3) << "\t" << frm_state(4) << "\t" << frm_state(5) << "\t" << frm_state(6)
+            << "\t" << frm_state(7) << "\t" << frm_state(8) << "\t" << frm_state(9)
+            << "\t" << frm_state(10) << "\t" << frm_state(11) << "\t" << frm_state(12) << "\t" << frm_state(13) << "\t" << frm_state(14) << "\t" << frm_state(15)
+            << "\t" << cov_stdev(0) << "\t" << cov_stdev(1) << "\t" << cov_stdev(2)
+            << "\t" << cov_stdev(3) << "\t" << cov_stdev(4) << "\t" << cov_stdev(5) << "\t" << cov_stdev(6)
+            << "\t" << cov_stdev(7) << "\t" << cov_stdev(8) << "\t" << cov_stdev(9)
+            << "\t" << cov_stdev(10) << "\t" << cov_stdev(11) << "\t" << cov_stdev(12) << "\t" << cov_stdev(13) << "\t" << cov_stdev(14) << "\t" << cov_stdev(15) << std::endl;
+        }
+    }
+
+    //trials to print all constraintIMUs' residuals
+    Eigen::Matrix<wolf::Scalar,15,1> IMU_residuals;
+    Eigen::Vector3s p1(Eigen::Vector3s::Zero());
+    Eigen::Vector4s q1_vec(Eigen::Vector4s::Zero());
+    Eigen::Map<Quaternions> q1(q1_vec.data());
+    Eigen::Vector3s v1(Eigen::Vector3s::Zero());
+    Eigen::Vector3s ab1(Eigen::Vector3s::Zero());
+    Eigen::Vector3s wb1(Eigen::Vector3s::Zero());
+    Eigen::Vector3s p2(Eigen::Vector3s::Zero());
+    Eigen::Vector4s q2_vec(Eigen::Vector4s::Zero());
+    Eigen::Map<Quaternions> q2(q2_vec.data());
+    Eigen::Vector3s v2(Eigen::Vector3s::Zero());
+    Eigen::Vector3s ab2(Eigen::Vector3s::Zero());
+    Eigen::Vector3s wb2(Eigen::Vector3s::Zero());
+
+    for(FrameBasePtr frm_ptr : frame_list)
+    {
+        if(frm_ptr->isKey())
+        {
+            ConstraintBaseList ctr_list =  frm_ptr->getConstrainedByList();
+            for(ConstraintBasePtr ctr_ptr : ctr_list)
+            {
+                if(ctr_ptr->getTypeId() == CTR_IMU)
+                {
+                    //Eigen::VectorXs prev_KF_state(ctr_ptr->getFrameOtherPtr()->getState());
+                    //Eigen::VectorXs curr_KF_state(ctr_ptr->getFeaturePtr()->getFramePtr()->getState());
+                    p1      = ctr_ptr->getFrameOtherPtr()->getPPtr()->getState();
+                    q1_vec  = ctr_ptr->getFrameOtherPtr()->getOPtr()->getState();
+                    v1      = ctr_ptr->getFrameOtherPtr()->getVPtr()->getState();
+                    ab1     = std::static_pointer_cast<FrameIMU>(ctr_ptr->getFrameOtherPtr())->getAccBiasPtr()->getState();
+                    wb1     = std::static_pointer_cast<FrameIMU>(ctr_ptr->getFrameOtherPtr())->getGyroBiasPtr()->getState();
+
+                    p2      = ctr_ptr->getFeaturePtr()->getFramePtr()->getPPtr()->getState();
+                    q2_vec  = ctr_ptr->getFeaturePtr()->getFramePtr()->getOPtr()->getState();
+                    v2      = ctr_ptr->getFeaturePtr()->getFramePtr()->getVPtr()->getState();
+                    ab2     = std::static_pointer_cast<FrameIMU>(ctr_ptr->getFeaturePtr()->getFramePtr())->getAccBiasPtr()->getState();
+                    wb2     = std::static_pointer_cast<FrameIMU>(ctr_ptr->getFeaturePtr()->getFramePtr())->getGyroBiasPtr()->getState();
+
+                    std::static_pointer_cast<ConstraintIMU>(ctr_ptr)->getResiduals(p1, q1, v1, ab1, wb1, p2, q2, v2, ab2, wb2, IMU_residuals);
+                    std::cout << "IMU residuals : " << IMU_residuals.transpose() << std::endl;
+                }
+            }
+        }
+    }
+
+    debug_results.close();
+    WOLF_WARN("WARNING : DEBUG_RESULTS ACTIVATED - slows the process (writing results to result_debugs.dat file)")
+
+    #endif
+
+    return 0;
+
+}
+
+int _kbhit()
+{
+    struct timeval tv;
+    fd_set fds;
+    tv.tv_sec = 0;
+    tv.tv_usec = 0;
+    FD_ZERO(&fds);
+    FD_SET(STDIN_FILENO, &fds); //STDIN_FILENO is 0
+    select(STDIN_FILENO+1, &fds, NULL, NULL, &tv);
+    return FD_ISSET(STDIN_FILENO, &fds);
+}
diff --git a/src/examples/test_kf_callback.cpp b/src/examples/test_kf_callback.cpp
index a116b314b9a595e855764874a58c7bf263ad4f30..e20084cd4b04eaccbaa9695d5d7921ae650cffff 100644
--- a/src/examples/test_kf_callback.cpp
+++ b/src/examples/test_kf_callback.cpp
@@ -54,7 +54,7 @@ int main()
         problem->print(2, false, true, false); // print(level, constr_by, metric, state_blocks)
 
         cout << "Motion-----------------" << endl;
-        sen_odo->process(make_shared<CaptureMotion>(t, sen_odo, odo_data, 3, 3));
+        sen_odo->process(make_shared<CaptureMotion>(t, sen_odo, odo_data, 3, 3, 3, 0));
         cout << "x(" << t.get() << ") = " << problem->getCurrentState().transpose() << endl;
         problem->print(2, false, true, false); // print(level, constr_by, metric, state_blocks)
 
diff --git a/src/examples/test_mpu.cpp b/src/examples/test_mpu.cpp
index 61f1cf37a3b9bf7c7227cf3be012b6fd36f2cbfe..da544d90afe9e0b14632fede31173cdd80fd49e4 100644
--- a/src/examples/test_mpu.cpp
+++ b/src/examples/test_mpu.cpp
@@ -104,7 +104,7 @@ int main(int argc, char** argv)
     #endif
 
     // Wolf problem
-    ProblemPtr wolf_problem_ptr_ = Problem::create(FRM_PQVBB_3D);
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
     Eigen::VectorXs IMU_extrinsics(7);
     IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot
     SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, IntrinsicsBasePtr());
diff --git a/src/examples/test_processor_image_landmark.cpp b/src/examples/test_processor_image_landmark.cpp
index e92a7f8783ec08e75669d7bcca748990115bd39a..06495426a1de3b9ec4df946bf318589ce06902d4 100644
--- a/src/examples/test_processor_image_landmark.cpp
+++ b/src/examples/test_processor_image_landmark.cpp
@@ -138,7 +138,7 @@ int main(int argc, char** argv)
     // running CAPTURES preallocated
     CaptureImagePtr image;
     Vector6s data(Vector6s::Zero()); // will integrate this data repeatedly
-    CaptureMotionPtr cap_odo = std::make_shared<CaptureMotion>(t, sensor_odom, data, 7, 6);
+    CaptureMotionPtr cap_odo = std::make_shared<CaptureMotion>(t, sensor_odom, data, 6, 7, 6, 0);
     //=====================================================
 
 
diff --git a/src/examples/test_processor_imu_jacobians.cpp b/src/examples/test_processor_imu_jacobians.cpp
index 9520dc71edda9fb5fa36968cdf08b991331b1eb2..b01b753a549763a70b79b7f62243ef976d9a4517 100644
--- a/src/examples/test_processor_imu_jacobians.cpp
+++ b/src/examples/test_processor_imu_jacobians.cpp
@@ -40,7 +40,7 @@ int main(int argc, char** argv)
     data_ << 10,0.5,3, 100*deg_to_rad,110*deg_to_rad,30*deg_to_rad;
 
     // Wolf problem
-    ProblemPtr wolf_problem_ptr_ = Problem::create(FRM_PQVBB_3D);
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
     Eigen::VectorXs IMU_extrinsics(7);
     IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot
     //SensorBase* sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, nullptr);
@@ -49,7 +49,7 @@ int main(int argc, char** argv)
     // Set the origin
     t.set(0.0001); // clock in 0,1 ms ticks
     Eigen::VectorXs x0(16);
-    x0 << 0,1,0,  1,0,0,  0,0,0,1,  0,0,.000,  0,0,.000; // P Q V B B
+    x0 << 0,1,0,   0,0,0,1,  1,0,0,  0,0,.000,  0,0,.000; // P Q V B B
 
     //wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(x0, t);
 
@@ -64,11 +64,11 @@ int main(int argc, char** argv)
     Eigen::Matrix<wolf::Scalar,10,1> Delta0;
     Delta0 = Eigen::Matrix<wolf::Scalar,10,1>::Random();
     Delta0.head<3>() = Delta0.head<3>()*100;
-    Delta0.segment<3>(3) = Delta0.segment<3>(3)*10;
+    Delta0.tail<3>() = Delta0.tail<3>()*10;
     Eigen::Vector3s ang0, ang;
     ang0 << 120.08*deg_to_rad, 12.36*deg_to_rad, 54.32*deg_to_rad; 
-    //Delta0 << 0,0,0, 0,0,0, 1,0,0,0;
-    Eigen::Map<Eigen::Quaternions> Delta0_quat(Delta0.data()+6);
+    //Delta0 << 0,0,0, 0,0,0,1, 0,0,0;
+    Eigen::Map<Eigen::Quaternions> Delta0_quat(Delta0.data()+3);
     Delta0_quat = v2q(ang0);
     Delta0_quat.normalize();
     ang = q2v(Delta0_quat);
@@ -117,18 +117,18 @@ int main(int argc, char** argv)
 
      std::cout << "\n input data : \n" << data_ << std::endl;
 
-     new (&q_in_1) Eigen::Map<Eigen::Quaternions>(bias_jac.Delta0_.data() + 6);
+     new (&q_in_1) Eigen::Map<Eigen::Quaternions>(bias_jac.Delta0_.data() + 3);
      for(int i=0;i<3;i++){
          dDp_dab.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i).head(3) - bias_jac.Delta0_.head(3))/ddelta_bias;
-         dDv_dab.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i).segment(3,3) - bias_jac.Delta0_.segment(3,3))/ddelta_bias;
+         dDv_dab.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i).tail(3) - bias_jac.Delta0_.tail(3))/ddelta_bias;
 
          dDp_dwb.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i+3).head(3) - bias_jac.Delta0_.head(3))/ddelta_bias;
-         dDv_dwb.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i+3).segment(3,3) - bias_jac.Delta0_.segment(3,3))/ddelta_bias;
+         dDv_dwb.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i+3).tail(3) - bias_jac.Delta0_.tail(3))/ddelta_bias;
 
-         new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac.Deltas_noisy_vect_(i).data() + 6);
+         new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac.Deltas_noisy_vect_(i).data() + 3);
          dDq_dab.block<3,1>(0,i) = R2v( q_in_1.matrix().transpose() * q_in_2.matrix())/ddelta_bias;
 
-         new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac.Deltas_noisy_vect_(i+3).data() + 6);
+         new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac.Deltas_noisy_vect_(i+3).data() + 3);
          dDq_dwb.block<3,1>(0,i) = R2v( q_in_1.matrix().transpose() * q_in_2.matrix())/ddelta_bias;
          //std::cout << "matrix operation result :" << i << "\n" << q_in_1.matrix().transpose() * q_in_2.matrix() << std::endl;
          //std::cout << "matrix operation result to vector :" << i << "\n" << R2v( q_in_1.matrix().transpose() * q_in_2.matrix()) << std::endl;
@@ -267,8 +267,8 @@ int main(int argc, char** argv)
     Eigen::Matrix<wolf::Scalar,9,1> Delta_noise;
     Eigen::Matrix<wolf::Scalar,9,1> delta_noise;
 
-    Delta_noise << 0.00000001, 0.00000001, 0.00000001, 0.00000001, 0.00000001, 0.00000001, 0.0001, 0.0001, 0.0001;
-    delta_noise << 0.00000001, 0.00000001, 0.00000001, 0.00000001, 0.00000001, 0.00000001, 0.0001, 0.0001, 0.0001;
+    Delta_noise << 0.00000001, 0.00000001, 0.00000001,  0.0001, 0.0001, 0.0001,  0.00000001, 0.00000001, 0.00000001;
+    delta_noise << 0.00000001, 0.00000001, 0.00000001,  0.0001, 0.0001, 0.0001,  0.00000001, 0.00000001, 0.00000001;
 
     struct IMU_jac_deltas deltas_jac = processor_imu.finite_diff_noise(dt, data_, Delta_noise, delta_noise, Delta0);
 
@@ -276,8 +276,8 @@ int main(int argc, char** argv)
                             jacobian_delta_preint_vect_                                                            jacobian_delta_vect_
                             0: + 0,                                                                                 0: + 0
                             1: +dPx, 2: +dPy, 3: +dPz                                                               1: + dpx, 2: +dpy, 3: +dpz
-                            4: +dVx, 5: +dVy, 6: +dVz                                                               4: + dvx, 5: +dvy, 6: +dvz
-                            7: +dOx, 8: +dOy, 9: +dOz                                                               7: + dox, 8: +doy, 9: +doz
+                            4: +dOx, 5: +dOy, 6: +dOz                                                               4: + dox, 5: +doy, 6: +doz
+                            7: +dVx, 8: +dVy, 9: +dVz                                                               7: + dvx, 8: +dvy, 9: +dvz
     */
 
     Eigen::Matrix3s dDp_dP, dDp_dV, dDp_dO, dDv_dP, dDv_dV, dDv_dO, dDo_dP, dDo_dV, dDo_dO;
@@ -290,20 +290,20 @@ int main(int argc, char** argv)
         //dDp_dPx = ((P + dPx) - P)/dPx
         dDp_dP.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i).head(3) - deltas_jac.Delta0_.head(3))/Delta_noise(i);
         //Dp_dVx = ((V + dVx)*dt - V*dt)/dVx
-        dDp_dV.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i+3).segment(3,3)*dt - deltas_jac.Delta0_.segment(3,3)*dt)/Delta_noise(i+3);
+        dDp_dV.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i+6).tail(3)*dt - deltas_jac.Delta0_.tail(3)*dt)/Delta_noise(i+6);
         //dDp_dOx = (( dR(Theta) * exp(dThetax,0,0)*dp ) - ( dR(Theta)*dp ))/dThetax
-        remapJacDeltas_quat(deltas_jac, Dq_noisy, dq_noisy, i+6);
-        dDp_dO.block<3,1>(0,i) = ((Dq_noisy.matrix() * deltas_jac.delta0_.head(3)) - (Dq0.matrix()* deltas_jac.delta0_.head(3)))/Delta_noise(i+6);
+        remapJacDeltas_quat(deltas_jac, Dq_noisy, dq_noisy, i+3);
+        dDp_dO.block<3,1>(0,i) = ((Dq_noisy.matrix() * deltas_jac.delta0_.head(3)) - (Dq0.matrix()* deltas_jac.delta0_.head(3)))/Delta_noise(i+3);
 
         //dDv_dP = [0, 0, 0]
         //dDv_dVx = ((V + dVx) - V)/dVx
-        dDv_dV.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i+3).segment(3,3) - deltas_jac.Delta0_.segment(3,3))/Delta_noise(i+3);
+        dDv_dV.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i+6).tail(3) - deltas_jac.Delta0_.tail(3))/Delta_noise(i+6);
         //dDv_dOx = (( dR(Theta) * exp(dThetax,0,0)*dv ) - ( dR(Theta)*dv ))/dThetax
-        dDv_dO.block<3,1>(0,i) = ((Dq_noisy.matrix() * deltas_jac.delta0_.segment(3,3)) - (Dq0.matrix()* deltas_jac.delta0_.segment(3,3)))/Delta_noise(i+6);
+        dDv_dO.block<3,1>(0,i) = ((Dq_noisy.matrix() * deltas_jac.delta0_.tail(3)) - (Dq0.matrix()* deltas_jac.delta0_.tail(3)))/Delta_noise(i+3);
 
         //dDo_dP = dDo_dV = [0, 0, 0]
         //dDo_dOx = log( (dR(Theta) * dr(theta)).transpose() * (dR(Theta)*exp(dThetax,0,0)) * dr(theta) )/dThetax
-        dDo_dO.block<3,1>(0,i) = R2v( (Dq0.matrix() * dq0.matrix()).transpose() * (Dq_noisy.matrix() * dq0.matrix()) )/Delta_noise(i+6);
+        dDo_dO.block<3,1>(0,i) = R2v( (Dq0.matrix() * dq0.matrix()).transpose() * (Dq_noisy.matrix() * dq0.matrix()) )/Delta_noise(i+3);
 
         //dDp_dpx = ( dR*(p + dpx) - dR*(p))/dpx
         dDp_dp.block<3,1>(0,i) = ( (Dq0.matrix() * deltas_jac.delta_noisy_vect_(i).head(3)) - (Dq0.matrix() * deltas_jac.delta0_.head(3)) )/delta_noise(i);
@@ -311,12 +311,12 @@ int main(int argc, char** argv)
 
         //dDv_dp = [0, 0, 0]
         //dDv_dvx = ( dR*(v + dvx) - dR*(v))/dvx
-        dDv_dv.block<3,1>(0,i) = ( (Dq0 * deltas_jac.delta_noisy_vect_(i+3).segment(3,3)) - (Dq0 * deltas_jac.delta0_.segment(3,3)) )/delta_noise(i+3);
+        dDv_dv.block<3,1>(0,i) = ( (Dq0 * deltas_jac.delta_noisy_vect_(i+6).tail(3)) - (Dq0 * deltas_jac.delta0_.tail(3)) )/delta_noise(i+6);
         //dDv_do = [0, 0, 0]
 
         //dDo_dp = dDo_dv = [0, 0, 0]
         //dDo_dox = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta) * (dr(theta)*exp(dthetax,0,0)) )/dthetax
-        dDo_do.block<3,1>(0,i) = R2v( (Dq0.matrix() * dq0.matrix()).transpose() * (Dq0.matrix() * dq_noisy.matrix()) )/Delta_noise(i+6);
+        dDo_do.block<3,1>(0,i) = R2v( (Dq0.matrix() * dq0.matrix()).transpose() * (Dq0.matrix() * dq_noisy.matrix()) )/Delta_noise(i+3);
     }
 
     /* jacobians wrt deltas have PVQ form :
@@ -333,50 +333,50 @@ int main(int argc, char** argv)
         std::cout << "dDp_dP_a - dDp_dP : \n" << deltas_jac.jacobian_delta_preint_.block(0,0,3,3) - dDp_dP <<  "\n" << std::endl;
     }
 
-    if(dDp_dV.isApprox(deltas_jac.jacobian_delta_preint_.block(0,3,3,3), wolf::Constants::EPS) )
+    if(dDp_dV.isApprox(deltas_jac.jacobian_delta_preint_.block(0,6,3,3), wolf::Constants::EPS) )
         std::cout<< "dDp_dV jacobian is correct !" << std::endl;
     else{
         std::cout<< "\t\tdDp_dV jacobian is not correct ..." << std::endl;
-        std::cout << "dDp_dV : \n" << dDp_dV << "\n deltas_jac.jacobian_delta_preint_.block(0,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,3,3,3) << "\n" << std::endl;
-        std::cout << "dDp_dV_a - dDp_dV : \n" << deltas_jac.jacobian_delta_preint_.block(0,3,3,3) - dDp_dV <<  "\n" << std::endl;
+        std::cout << "dDp_dV : \n" << dDp_dV << "\n deltas_jac.jacobian_delta_preint_.block(0,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,6,3,3) << "\n" << std::endl;
+        std::cout << "dDp_dV_a - dDp_dV : \n" << deltas_jac.jacobian_delta_preint_.block(0,6,3,3) - dDp_dV <<  "\n" << std::endl;
     }
 
-    if(dDp_dO.isApprox(deltas_jac.jacobian_delta_preint_.block(0,6,3,3), wolf::Constants::EPS) )
+    if(dDp_dO.isApprox(deltas_jac.jacobian_delta_preint_.block(0,3,3,3), wolf::Constants::EPS) )
         std::cout<< "dDp_dO jacobian is correct !" << std::endl;
     else{
         std::cout<< "\t\tdDp_dO jacobian is not correct ..." << std::endl;
-        std::cout << "dDp_dO : \n" << dDp_dO << "\n deltas_jac.jacobian_delta_preint_.block(0,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,6,3,3) << "\n" << std::endl;
-        std::cout << "dDp_dO_a - dDp_dO : \n" << deltas_jac.jacobian_delta_preint_.block(0,6,3,3) - dDp_dO <<  "\n" << std::endl;
+        std::cout << "dDp_dO : \n" << dDp_dO << "\n deltas_jac.jacobian_delta_preint_.block(0,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,3,3,3) << "\n" << std::endl;
+        std::cout << "dDp_dO_a - dDp_dO : \n" << deltas_jac.jacobian_delta_preint_.block(0,3,3,3) - dDp_dO <<  "\n" << std::endl;
     }
 
-    if(dDv_dV.isApprox(deltas_jac.jacobian_delta_preint_.block(3,3,3,3), wolf::Constants::EPS) )
+    if(dDv_dV.isApprox(deltas_jac.jacobian_delta_preint_.block(6,6,3,3), wolf::Constants::EPS) )
         std::cout<< "dDv_dV jacobian is correct !" << std::endl;
     else{
         std::cout<< "\t\tdDv_dV jacobian is not correct ..." << std::endl;
-        std::cout << "dDv_dV : \n" << dDv_dV << "\n deltas_jac.jacobian_delta_preint_.block(3,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(3,3,3,3) << "\n" << std::endl;
-        std::cout << "dDv_dV_a - dDv_dV : \n" << deltas_jac.jacobian_delta_preint_.block(3,3,3,3) - dDv_dV <<  "\n" << std::endl;    
+        std::cout << "dDv_dV : \n" << dDv_dV << "\n deltas_jac.jacobian_delta_preint_.block(6,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(6,6,3,3) << "\n" << std::endl;
+        std::cout << "dDv_dV_a - dDv_dV : \n" << deltas_jac.jacobian_delta_preint_.block(6,6,3,3) - dDv_dV <<  "\n" << std::endl;    
     }
 
-    if(dDv_dO.isApprox(deltas_jac.jacobian_delta_preint_.block(3,6,3,3), wolf::Constants::EPS) )
+    if(dDv_dO.isApprox(deltas_jac.jacobian_delta_preint_.block(6,3,3,3), wolf::Constants::EPS) )
         std::cout<< "dDv_dO jacobian is correct !" << std::endl;
     else{
         std::cout<< "\t\tdDv_dO jacobian is not correct ..." << std::endl;
-        std::cout << "dDv_dO : \n" << dDv_dO << "\n deltas_jac.jacobian_delta_preint_.block(3,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(3,6,3,3) << "\n" << std::endl;
-        std::cout << "dDv_dO_a - dDv_dO : \n" << deltas_jac.jacobian_delta_preint_.block(3,6,3,3) - dDv_dO <<  "\n" << std::endl;
+        std::cout << "dDv_dO : \n" << dDv_dO << "\n deltas_jac.jacobian_delta_preint_.block(6,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(6,3,3,3) << "\n" << std::endl;
+        std::cout << "dDv_dO_a - dDv_dO : \n" << deltas_jac.jacobian_delta_preint_.block(6,3,3,3) - dDv_dO <<  "\n" << std::endl;
     }
 
-    if(dDo_dO.isApprox(deltas_jac.jacobian_delta_preint_.block(6,6,3,3), wolf::Constants::EPS) )
+    if(dDo_dO.isApprox(deltas_jac.jacobian_delta_preint_.block(3,3,3,3), wolf::Constants::EPS) )
         std::cout<< "dDo_dO jacobian is correct !" << std::endl;
     else{
         std::cout<< "\t\tdDo_dO jacobian is not correct ..." << std::endl;
-        std::cout << "dDo_dO : \n" << dDo_dO << "\n deltas_jac.jacobian_delta_preint_.block(6,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(6,6,3,3) << "\n" << std::endl;
-        std::cout << "dDo_dO_a - dDo_dO : \n" << deltas_jac.jacobian_delta_preint_.block(6,6,3,3) - dDo_dO <<  "\n" << std::endl;
+        std::cout << "dDo_dO : \n" << dDo_dO << "\n deltas_jac.jacobian_delta_preint_.block(3,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(3,3,3,3) << "\n" << std::endl;
+        std::cout << "dDo_dO_a - dDo_dO : \n" << deltas_jac.jacobian_delta_preint_.block(3,3,3,3) - dDo_dO <<  "\n" << std::endl;
     }
 
      Eigen::Matrix3s dDp_dp_a, dDv_dv_a, dDo_do_a;
      dDp_dp_a = deltas_jac.jacobian_delta_.block(0,0,3,3);
-     dDv_dv_a = deltas_jac.jacobian_delta_.block(3,3,3,3);
-     dDo_do_a = deltas_jac.jacobian_delta_.block(6,6,3,3);
+     dDv_dv_a = deltas_jac.jacobian_delta_.block(6,6,3,3);
+     dDo_do_a = deltas_jac.jacobian_delta_.block(3,3,3,3);
 
     if(dDp_dp.isApprox(dDp_dp_a, wolf::Constants::EPS) )
         std::cout<< "dDp_dp jacobian is correct !" << std::endl;
@@ -409,13 +409,13 @@ using namespace wolf;
 
 void remapJacDeltas_quat0(IMU_jac_deltas& _jac_delta, Eigen::Map<Eigen::Quaternions>& _Dq0, Eigen::Map<Eigen::Quaternions>& _dq0){
 
-        new (&_Dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta0_.data() + 6);
-        new (&_dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta0_.data() + 6);
+        new (&_Dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta0_.data() + 3);
+        new (&_dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta0_.data() + 3);
 }
 
 void remapJacDeltas_quat(IMU_jac_deltas& _jac_delta, Eigen::Map<Eigen::Quaternions>& _Dq, Eigen::Map<Eigen::Quaternions>& _dq, const int& place ){
     
     assert(place < _jac_delta.Delta_noisy_vect_.size());
-    new (&_Dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta_noisy_vect_(place).data() + 6);
-    new (&_dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta_noisy_vect_(place).data() + 6);
+    new (&_Dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta_noisy_vect_(place).data() + 3);
+    new (&_dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta_noisy_vect_(place).data() + 3);
 }
diff --git a/src/examples/test_processor_odom_3D.cpp b/src/examples/test_processor_odom_3D.cpp
index a495f11d83e23d539eb7547fa5eab746001dec99..c43b1f50807d259e8f8a13da6ea8a9701a7771b9 100644
--- a/src/examples/test_processor_odom_3D.cpp
+++ b/src/examples/test_processor_odom_3D.cpp
@@ -62,7 +62,7 @@ int main (int argc, char** argv)
 
     Scalar dt = 0.1;
 
-    CaptureMotionPtr cap_odo = std::make_shared<CaptureMotion>(TimeStamp(0), sen, data, 7, 6);
+    CaptureMotionPtr cap_odo = std::make_shared<CaptureMotion>(TimeStamp(0), sen, data, 7, 7, 6, 0 );
 
     cout << "t: " << std::setprecision(2) << 0 << "  \t x = ( " << problem->getCurrentState().transpose() << ")" << endl;
 
diff --git a/src/examples/test_simple_AHP.cpp b/src/examples/test_simple_AHP.cpp
index 08b76d7ee0343f426f4226cf6d161ff201f078ba..d31eba5ab0db4735847ec354b13dcb6ddb206812 100644
--- a/src/examples/test_simple_AHP.cpp
+++ b/src/examples/test_simple_AHP.cpp
@@ -159,11 +159,11 @@ int main(int argc, char** argv)
     std::cout << "Landmark 1: " << lmk_1->point().transpose() << std::endl;
 
     // Constraints------------------
-    ConstraintAHPPtr ctr_0 = ConstraintAHP::create(feat_0, lmk_1 );
+    ConstraintAHPPtr ctr_0 = ConstraintAHP::create(feat_0, lmk_1, nullptr);
     feat_0->addConstraint(ctr_0);
-    ConstraintAHPPtr ctr_1 = ConstraintAHP::create(feat_1, lmk_1 );
+    ConstraintAHPPtr ctr_1 = ConstraintAHP::create(feat_1, lmk_1, nullptr);
     feat_1->addConstraint(ctr_1);
-    ConstraintAHPPtr ctr_2 = ConstraintAHP::create(feat_2, lmk_1 );
+    ConstraintAHPPtr ctr_2 = ConstraintAHP::create(feat_2, lmk_1, nullptr);
     feat_2->addConstraint(ctr_2);
 
     // Projections----------------------------
@@ -210,9 +210,9 @@ int main(int argc, char** argv)
     std::cout << "Landmark 2: " << lmk_2->point().transpose() << std::endl;
 
     // New constraints from kf3 and kf4
-    ConstraintAHPPtr ctr_3 = ConstraintAHP::create(feat_3, lmk_2 );
+    ConstraintAHPPtr ctr_3 = ConstraintAHP::create(feat_3, lmk_2, nullptr);
     feat_3->addConstraint(ctr_3);
-    ConstraintAHPPtr ctr_4 = ConstraintAHP::create(feat_4, lmk_2 );
+    ConstraintAHPPtr ctr_4 = ConstraintAHP::create(feat_4, lmk_2, nullptr);
     feat_4->addConstraint(ctr_4);
 
     Eigen::Vector2s pix_3 = ctr_3->expectation();
diff --git a/src/factory.h b/src/factory.h
index 6a754ba748426cea0c2ee95ac14602c00b3cd6d8..00d2263c2657c183bd6ac1204198ece06ce4ea9e 100644
--- a/src/factory.h
+++ b/src/factory.h
@@ -355,9 +355,27 @@ inline std::string FrameFactory::getClass()
 {
     return "FrameFactory";
 }
+
+//#define UNUSED(x) (void)x;
+//#define UNUSED(x) (void)(sizeof((x), 0));
+
+#ifdef __GNUC__
+    #define WOLF_UNUSED __attribute__((used))
+#elif defined _MSC_VER
+    #pragma warning(disable: Cxxxxx)
+    #define WOLF_UNUSED
+#elif defined(__LCLINT__)
+# define WOLF_UNUSED /*@unused@*/
+#elif defined(__cplusplus)
+# define WOLF_UNUSED
+#else
+# define UNUSED(x) x
+#endif
+
 #define WOLF_REGISTER_FRAME(FrameType, FrameName) \
-  namespace{ const bool FrameName##Registered = \
-    FrameFactory::get().registerCreator(FrameType, FrameName::create); }\
+  namespace{ const bool WOLF_UNUSED FrameName##Registered = \
+    wolf::FrameFactory::get().registerCreator(FrameType, FrameName::create); }\
+
 
 } /* namespace wolf */
 
diff --git a/src/feature_base.cpp b/src/feature_base.cpp
index 5eee05e44f83ef53b0bbd62498b8aed1ca43bdab..13b9987f5c8adcdb8add385aae6c3e10c584707f 100644
--- a/src/feature_base.cpp
+++ b/src/feature_base.cpp
@@ -82,7 +82,7 @@ void FeatureBase::setMeasurementCovariance(const Eigen::MatrixXs & _meas_cov)
     assert(_meas_cov.determinant() > 0 && "Not positive definite measurement covariance");
 
     measurement_covariance_ = _meas_cov;
-	measurement_sqrt_information_upper_ = computeSqrtUpper(_meas_cov.inverse());
+	measurement_sqrt_information_upper_ = computeSqrtUpper(_meas_cov);
 }
 
 void FeatureBase::setMeasurementInfo(const Eigen::MatrixXs & _meas_info)
@@ -90,14 +90,24 @@ void FeatureBase::setMeasurementInfo(const Eigen::MatrixXs & _meas_info)
     assert(_meas_info.determinant() > 0 && "Not positive definite measurement information");
 
     measurement_covariance_ = _meas_info.inverse();
-    measurement_sqrt_information_upper_ = computeSqrtUpper(_meas_info);
+    measurement_sqrt_information_upper_ = computeSqrtUpper(_meas_info.inverse());
 }
 
-Eigen::MatrixXs FeatureBase::computeSqrtUpper(const Eigen::MatrixXs & _M) const
+Eigen::MatrixXs FeatureBase::computeSqrtUpper(const Eigen::MatrixXs & _covariance) const
 {
-    assert(_M.determinant() > 0 && "Matrix is not positive definite!");
-    Eigen::LLT<Eigen::MatrixXs> llt_of_info(_M);
-    return llt_of_info.matrixU();
+    if (_covariance.determinant() < Constants::EPS_SMALL)
+    {
+        // Avoid singular covariances matrix
+        Eigen::MatrixXs cov = _covariance + 1e-8 * Eigen::MatrixXs::Identity(_covariance.rows(), _covariance.cols());
+        Eigen::LLT<Eigen::MatrixXs> llt_of_info(cov.inverse());
+        return llt_of_info.matrixU();
+    }
+    else
+    {
+        // Normal operation
+        Eigen::LLT<Eigen::MatrixXs> llt_of_info(_covariance.inverse());
+        return llt_of_info.matrixU();
+    }
 }
 
 } // namespace wolf
diff --git a/src/feature_corner_2D.cpp b/src/feature_corner_2D.cpp
index e1414f463cf62602ad1d14372ab932a4302ea8be..59db17e3b425f0243f2048b5d9a65f4f30155bcf 100644
--- a/src/feature_corner_2D.cpp
+++ b/src/feature_corner_2D.cpp
@@ -4,7 +4,7 @@
 namespace wolf {
 
 FeatureCorner2D::FeatureCorner2D(const Eigen::Vector4s & _measurement, const Eigen::Matrix4s & _meas_covariance) :
-    FeatureBase("CORNER", _measurement, _meas_covariance)
+    FeatureBase("CORNER 2D", _measurement, _meas_covariance)
 {
     //std::cout << "feature: "<< _measurement.transpose() << std::endl;
 }
diff --git a/src/feature_imu.cpp b/src/feature_imu.cpp
index 91dd5c1823ea26d4fbae127c5d6813649fcfe399..19e37f81e0c0f1fc849a8a4ebbbd355d118eb302 100644
--- a/src/feature_imu.cpp
+++ b/src/feature_imu.cpp
@@ -3,11 +3,43 @@
 namespace wolf {
 
 FeatureIMU::FeatureIMU(const Eigen::VectorXs& _delta_preintegrated, const Eigen::MatrixXs& _delta_preintegrated_covariance) :
-    FeatureBase("IMU", _delta_preintegrated, _delta_preintegrated_covariance)
+    FeatureBase("IMU", _delta_preintegrated, _delta_preintegrated_covariance),
+    dp_preint_(_delta_preintegrated.head<3>()),dv_preint_(_delta_preintegrated.tail<3>()), dq_preint_(_delta_preintegrated.segment<4>(3))
 {
     //std::cout << "New FeatureIMU: measurement " << _measurement.transpose() << std::endl << "covariance" << std::endl << _meas_covariance << std::endl;
 }
 
+FeatureIMU::FeatureIMU(const Eigen::VectorXs& _delta_preintegrated, const Eigen::MatrixXs& _delta_preintegrated_covariance, const Eigen::Vector3s& _acc_bias, const Eigen::Vector3s& _gyro_bias, const Eigen::Matrix<wolf::Scalar,9,6>& _dD_db_jacobians) :
+    FeatureBase("IMU", _delta_preintegrated, _delta_preintegrated_covariance),
+    dp_preint_(_delta_preintegrated.head<3>()),dv_preint_(_delta_preintegrated.tail<3>()), dq_preint_(_delta_preintegrated.segment<4>(3)),
+    acc_bias_preint_(_acc_bias), gyro_bias_preint_(_gyro_bias),
+    dDp_dab_(_dD_db_jacobians.block(0,0,3,3)), dDv_dab_(_dD_db_jacobians.block(6,0,3,3)),
+    dDp_dwb_(_dD_db_jacobians.block(0,3,3,3)), dDv_dwb_(_dD_db_jacobians.block(6,3,3,3)), dDq_dwb_(_dD_db_jacobians.block(3,3,3,3))
+{
+    //std::cout << "New FeatureIMU: measurement " << _measurement.transpose() << std::endl << "covariance" << std::endl << _meas_covariance << std::endl;
+}
+
+FeatureIMU::FeatureIMU(const Eigen::VectorXs& _delta_preintegrated, const Eigen::MatrixXs& _delta_preintegrated_covariance, const wolf::CaptureIMUPtr _cap_imu_ptr, const Eigen::Matrix<wolf::Scalar,9,6>& _dD_db_jacobians): 
+FeatureBase("IMU", _delta_preintegrated, _delta_preintegrated_covariance)
+{
+    //TODO : SIZE ASSERTIONS : make sure _delta_preintegrated and _delta_preintegrated_covariance sizes are correct !
+
+    this->setCapturePtr(_cap_imu_ptr);
+    //TODO : we should make sure here that there is a frame in the capture
+    dp_preint_ = _delta_preintegrated.head<3>();
+    dv_preint_ = _delta_preintegrated.tail<3>();
+    dq_preint_ = _delta_preintegrated.segment<4>(3);
+
+    acc_bias_preint_ = std::static_pointer_cast<wolf::FrameIMU>(_cap_imu_ptr->getFramePtr())->getAccBiasPtr()->getState();
+    gyro_bias_preint_ = std::static_pointer_cast<wolf::FrameIMU>(_cap_imu_ptr->getFramePtr())->getGyroBiasPtr()->getState();
+
+    dDp_dab_ = _dD_db_jacobians.block(0,0,3,3);
+    dDv_dab_ = _dD_db_jacobians.block(6,0,3,3);
+    dDp_dwb_ = _dD_db_jacobians.block(0,3,3,3);
+    dDv_dwb_ = _dD_db_jacobians.block(6,3,3,3); 
+    dDq_dwb_ = _dD_db_jacobians.block(3,3,3,3);
+}
+
 FeatureIMU::~FeatureIMU()
 {
     //
diff --git a/src/feature_imu.h b/src/feature_imu.h
index a1933685742a9ac172734f5bbf198ebbc715dcf4..255adac855cb76c40a31fe2ade98723619fd03a0 100644
--- a/src/feature_imu.h
+++ b/src/feature_imu.h
@@ -3,12 +3,16 @@
 
 //Wolf includes
 #include "feature_base.h"
+#include "capture_imu.h"
+#include "frame_imu.h"
+#include "wolf.h"
 
 //std includes
 
 
 namespace wolf {
-    
+
+WOLF_PTR_TYPEDEFS(CaptureIMU);
 WOLF_PTR_TYPEDEFS(FeatureIMU);
 
 //class FeatureIMU
@@ -24,6 +28,28 @@ class FeatureIMU : public FeatureBase
          */
         FeatureIMU(const Eigen::VectorXs& _delta_preintegrated, const Eigen::MatrixXs& _delta_preintegrated_covariance);
 
+        /** \brief Constructor from capture pointer and measure
+         *
+         * \param _measurement the measurement
+         * \param _meas_covariance the noise of the measurement
+         * \param _dD_db_jacobians Jacobians of preintegrated delta wrt IMU biases
+         * \param acc_bias accelerometer bias of origin frame
+         * \param gyro_bias gyroscope bias of origin frame
+         *
+         */
+        FeatureIMU(const Eigen::VectorXs& _delta_preintegrated, const Eigen::MatrixXs& _delta_preintegrated_covariance, 
+        const Eigen::Vector3s& _acc_bias, const Eigen::Vector3s& _gyro_bias, const Eigen::Matrix<wolf::Scalar,9,6>& _dD_db_jacobians);
+
+        /** \brief Constructor from capture pointer and measure
+         *
+         * \param _measurement the measurement
+         * \param _meas_covariance the noise of the measurement
+         * \param _dD_db_jacobians Jacobians of preintegrated delta wrt IMU biases
+         * \param _cap_imu_ptr is the CaptureIMUPtr pointing to desired capture containing the origin frame
+         *
+         */
+        FeatureIMU(const Eigen::VectorXs& _delta_preintegrated, const Eigen::MatrixXs& _delta_preintegrated_covariance, const wolf::CaptureIMUPtr _cap_imu_ptr, const Eigen::Matrix<wolf::Scalar,9,6>& _dD_db_jacobians);
+
         virtual ~FeatureIMU();
 
     public: // TODO eventually produce getters for these and then go private
diff --git a/src/frame_base.cpp b/src/frame_base.cpp
index 046983d087bfd15b2f3cfd1a206c3e6db2f57707..50f6e8bbf0f71afe99e0a7e38f71a9fca4ea246f 100644
--- a/src/frame_base.cpp
+++ b/src/frame_base.cpp
@@ -134,12 +134,16 @@ void FrameBase::setState(const Eigen::VectorXs& _st)
         size += (state_block_vec_[i]==nullptr ? 0 : state_block_vec_[i]->getSize());
     }
     
-    assert(_st.size() == size && "In FrameBase::setState wrong state size");
+    //State Vector size must be lower or equal to frame state size :
+    // example : PQVBB -> if we initialize only position and orientation due to use of processorOdom3D
+    assert(_st.size() <= size && "In FrameBase::setState wrong state size");
 
     unsigned int index = 0;
+    const unsigned int _st_size = _st.size();
 
+    //initialize the FrameBase StateBlocks while StateBlocks list's end not reached and input state_size can go further 
     for (StateBlockPtr sb : state_block_vec_)
-        if (sb)
+        if (sb && (index < _st_size))
         {
             sb->setState(_st.segment(index, sb->getSize()));
             index += sb->getSize();
@@ -306,7 +310,7 @@ FrameBasePtr FrameBase::create_POV_3D(const FrameType & _tp,
 #include "factory.h"
 namespace wolf
 {
-namespace{ const bool Frame_PO_2D_Registered  = FrameFactory::get().registerCreator("PO 2D",  FrameBase::create_PO_2D ); }
-namespace{ const bool Frame_PO_3D_Registered  = FrameFactory::get().registerCreator("PO 3D",  FrameBase::create_PO_3D ); }
-namespace{ const bool Frame_POV_3D_Registered = FrameFactory::get().registerCreator("POV 3D", FrameBase::create_POV_3D); }
+namespace{ const bool WOLF_UNUSED Frame_PO_2D_Registered  = FrameFactory::get().registerCreator("PO 2D",  FrameBase::create_PO_2D ); }
+namespace{ const bool WOLF_UNUSED Frame_PO_3D_Registered  = FrameFactory::get().registerCreator("PO 3D",  FrameBase::create_PO_3D ); }
+namespace{ const bool WOLF_UNUSED Frame_POV_3D_Registered = FrameFactory::get().registerCreator("POV 3D", FrameBase::create_POV_3D); }
 } // namespace wolf
diff --git a/src/frame_base.h b/src/frame_base.h
index fab2146dc52cde3897ef6817cea0260a879236ca..408b6b0bc9f061fd3e6bb703bd829a88f80bef09 100644
--- a/src/frame_base.h
+++ b/src/frame_base.h
@@ -221,12 +221,12 @@ inline void FrameBase::setTimeStamp(const TimeStamp& _ts)
 
 inline void FrameBase::getTimeStamp(TimeStamp& _ts) const
 {
-    _ts = time_stamp_.get();
+    _ts = time_stamp_;
 }
 
 inline TimeStamp FrameBase::getTimeStamp() const
 {
-    return time_stamp_.get();
+    return time_stamp_;
 }
 
 inline const std::vector<StateBlockPtr>& FrameBase::getStateBlockVec() const
diff --git a/src/frame_imu.cpp b/src/frame_imu.cpp
index 3c8160ccd1052314c2a3fcf27f5a360a3898bfb0..0b2f527361633b8d7a1d21ec8382ee6787fa187e 100644
--- a/src/frame_imu.cpp
+++ b/src/frame_imu.cpp
@@ -8,13 +8,13 @@
 namespace wolf {
 
 FrameIMU::FrameIMU(const FrameType& _tp, const TimeStamp& _ts, const Eigen::VectorXs& _x) :
-        FrameBase(_tp, _ts, std::make_shared<StateBlock>(3), std::make_shared<StateQuaternion>(), std::make_shared<StateBlock>(3))
+        FrameBase(_tp, _ts, std::make_shared<StateBlock>(_x.head(3)), std::make_shared<StateQuaternion>(_x.segment(3,4)), std::make_shared<StateBlock>(_x.segment(7,3)))
 {
     assert(_x.size() == 16 && "Wrong vector size! Must be 16.");
 
     resizeStateBlockVec(5); // could have done push_back, but prefer more explicit locations for the StateBlocks
-    setStateBlockPtr(3, std::make_shared<StateBlock>(3)); // acc bias
-    setStateBlockPtr(4, std::make_shared<StateBlock>(3)); // gyro bias
+    setStateBlockPtr(3, std::make_shared<StateBlock>(_x.segment(10,3))); // acc bias
+    setStateBlockPtr(4, std::make_shared<StateBlock>(_x.tail(3))); // gyro bias
     setState(_x);
     setType("IMU");
 }
@@ -43,5 +43,5 @@ FrameBasePtr FrameIMU::create(const FrameType & _tp,
 namespace wolf
 {
 WOLF_REGISTER_FRAME("IMU", FrameIMU);
-namespace{ const bool Frame_PQVBB_3D_Registered = FrameFactory::get().registerCreator("PQVBB 3D", FrameIMU::create); } // alternate name possible
+namespace{ const bool WOLF_UNUSED Frame_PQVBB_3D_Registered = FrameFactory::get().registerCreator("PQVBB 3D", FrameIMU::create); } // alternate name possible
 } // namespace wolf
diff --git a/src/imu_tools.h b/src/imu_tools.h
new file mode 100644
index 0000000000000000000000000000000000000000..a1831bde54104c142533510dbb64afca79f37a01
--- /dev/null
+++ b/src/imu_tools.h
@@ -0,0 +1,446 @@
+/*
+ * imu_tools.h
+ *
+ *  Created on: Jul 29, 2017
+ *      Author: jsola
+ */
+
+#ifndef IMU_TOOLS_H_
+#define IMU_TOOLS_H_
+
+
+#include "wolf.h"
+#include "rotations.h"
+
+namespace wolf 
+{
+namespace imu {
+using namespace Eigen;
+
+template<typename D1, typename D2, typename D3>
+inline void identity(MatrixBase<D1>& p, QuaternionBase<D2>& q, MatrixBase<D3>& v)
+{
+    p = MatrixBase<D1>::Zero(3,1);
+    q = QuaternionBase<D2>::Identity();
+    v = MatrixBase<D3>::Zero(3,1);
+}
+
+template<typename D1, typename D2, typename D3>
+inline void identity(MatrixBase<D1>& p, MatrixBase<D2>& q, MatrixBase<D3>& v)
+{
+    typedef typename D1::Scalar T1;
+    typedef typename D2::Scalar T2;
+    typedef typename D3::Scalar T3;
+    p << T1(0), T1(0), T1(0);
+    q << T2(0), T2(0), T2(0), T2(1);
+    v << T3(0), T3(0), T3(0);
+}
+
+template<typename T = wolf::Scalar>
+inline Matrix<T, 10, 1> identity()
+{
+    Matrix<T, 10, 1> ret;
+    ret<< T(0), T(0), T(0),
+          T(0), T(0), T(0), T(1),
+          T(0), T(0), T(0);
+    return ret;
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, typename D6, class T>
+inline void inverse(const MatrixBase<D1>& dp, const QuaternionBase<D2>& dq, const MatrixBase<D3>& dv,
+                    const T dt,
+                    MatrixBase<D4>& idp, QuaternionBase<D5>& idq, MatrixBase<D6>& idv )
+{
+    MatrixSizeCheck<3, 1>::check(dp);
+    MatrixSizeCheck<3, 1>::check(dv);
+    MatrixSizeCheck<3, 1>::check(idp);
+    MatrixSizeCheck<3, 1>::check(idv);
+
+    idp = - ( dq.conjugate() * (dp - dv * typename D3::Scalar(dt) ) );
+    idv = - ( dq.conjugate() * dv );
+    idq =     dq.conjugate();
+}
+
+template<typename D1, typename D2, class T>
+inline void inverse(const MatrixBase<D1>& d,
+                    T dt,
+                    MatrixBase<D2>& id)
+{
+    MatrixSizeCheck<10, 1>::check(d);
+    MatrixSizeCheck<10, 1>::check(id);
+
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dp   ( & d( 0 ) );
+    Map<const Quaternion<typename D1::Scalar> >     dq   ( & d( 3 ) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dv   ( & d( 7 ) );
+    Map<Matrix<typename D2::Scalar, 3, 1> >         idp  ( & id( 0 ) );
+    Map<Quaternion<typename D2::Scalar> >           idq  ( & id( 3 ) );
+    Map<Matrix<typename D2::Scalar, 3, 1> >         idv  ( & id( 7 ) );
+
+    inverse(dp, dq, dv, dt, idp, idq, idv);
+}
+
+template<typename D, class T>
+inline Matrix<typename D::Scalar, 10, 1> inverse(const MatrixBase<D>& d,
+                                                 T dt)
+{
+    Matrix<typename D::Scalar, 10, 1> id;
+    inverse(d, dt, id);
+    return id;
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, typename D6, typename D7, typename D8, typename D9, class T>
+inline void compose(const MatrixBase<D1>& dp1, const QuaternionBase<D2>& dq1, const MatrixBase<D3>& dv1,
+                    const MatrixBase<D4>& dp2, const QuaternionBase<D5>& dq2, const MatrixBase<D6>& dv2,
+                    const T dt,
+                    MatrixBase<D7>& sum_p, QuaternionBase<D8>& sum_q, MatrixBase<D9>& sum_v )
+{
+        MatrixSizeCheck<3, 1>::check(dp1);
+        MatrixSizeCheck<3, 1>::check(dv1);
+        MatrixSizeCheck<3, 1>::check(dp2);
+        MatrixSizeCheck<3, 1>::check(dv2);
+        MatrixSizeCheck<3, 1>::check(sum_p);
+        MatrixSizeCheck<3, 1>::check(sum_v);
+
+        sum_p = dp1 + dv1*dt + dq1*dp2;
+        sum_v = dv1 +          dq1*dv2;
+        sum_q =                dq1*dq2; // dq here to avoid possible aliasing between d1 and sum
+}
+
+template<typename D1, typename D2, typename D3, class T>
+inline void compose(const MatrixBase<D1>& d1,
+                    const MatrixBase<D2>& d2,
+                    T dt,
+                    MatrixBase<D3>& sum)
+{
+    MatrixSizeCheck<10, 1>::check(d1);
+    MatrixSizeCheck<10, 1>::check(d2);
+    MatrixSizeCheck<10, 1>::check(sum);
+
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dp1    ( & d1( 0 ) );
+    Map<const Quaternion<typename D1::Scalar> >     dq1    ( & d1( 3 ) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dv1    ( & d1( 7 ) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dp2    ( & d2( 0 ) );
+    Map<const Quaternion<typename D2::Scalar> >     dq2    ( & d2( 3 ) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dv2    ( & d2( 7 ) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         sum_p  ( & sum( 0 ) );
+    Map<Quaternion<typename D3::Scalar> >           sum_q  ( & sum( 3 ) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         sum_v  ( & sum( 7 ) );
+
+    compose(dp1, dq1, dv1, dp2, dq2, dv2, dt, sum_p, sum_q, sum_v);
+}
+
+template<typename D1, typename D2, class T>
+inline Matrix<typename D1::Scalar, 10, 1> compose(const MatrixBase<D1>& d1,
+                                                  const MatrixBase<D2>& d2,
+                                                  T dt)
+{
+    Matrix<typename D1::Scalar, 10, 1>  ret;
+    compose(d1, d2, dt, ret);
+    return ret;
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, class T>
+inline void compose(const MatrixBase<D1>& d1,
+                    const MatrixBase<D2>& d2,
+                    T dt,
+                    MatrixBase<D3>& sum,
+                    MatrixBase<D4>& J_sum_d1,
+                    MatrixBase<D5>& J_sum_d2)
+{
+    MatrixSizeCheck<10, 1>::check(d1);
+    MatrixSizeCheck<10, 1>::check(d2);
+    MatrixSizeCheck<10, 1>::check(sum);
+    MatrixSizeCheck< 9, 9>::check(J_sum_d1);
+    MatrixSizeCheck< 9, 9>::check(J_sum_d2);
+
+    // Maps over provided data
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dp1    ( & d1( 0 ) );
+    Map<const Quaternion<typename D1::Scalar> >     dq1    ( & d1( 3 ) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dv1    ( & d1( 7 ) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dp2    ( & d2( 0 ) );
+    Map<const Quaternion<typename D2::Scalar> >     dq2    ( & d2( 3 ) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dv2    ( & d2( 7 ) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         sum_p  ( & sum( 0 ) );
+    Map<Quaternion<typename D3::Scalar> >           sum_q  ( & sum( 3 ) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         sum_v  ( & sum( 7 ) );
+
+    // Some useful temporaries
+    Matrix<typename D1::Scalar, 3, 3> dR1 = dq1.matrix(); // First  Delta, DR
+    Matrix<typename D2::Scalar, 3, 3> dR2 = dq2.matrix(); // Second delta, dR
+
+    // Jac wrt first delta
+    J_sum_d1.setIdentity();                                     // dDp'/dDp = dDv'/dDv = I
+    J_sum_d1.block(0,3,3,3).noalias() = - dR1 * skew(dp2) ;     // dDp'/dDo
+    J_sum_d1.block(0,6,3,3) = Matrix3s::Identity() * dt;        // dDp'/dDv = I*dt
+    J_sum_d1.block(3,3,3,3) = dR2.transpose();                  // dDo'/dDo
+    J_sum_d1.block(6,3,3,3).noalias() = - dR1 * skew(dv2) ;     // dDv'/dDo
+
+    // Jac wrt second delta
+    J_sum_d2.setIdentity();                                     //
+    J_sum_d2.block(0,0,3,3) = dR1;                              // dDp'/ddp
+    J_sum_d2.block(6,6,3,3) = dR1;                              // dDv'/ddv
+    // J_sum_d2.block(3,3,3,3) = Matrix3s::Identity();          // dDo'/ddo = I
+
+    // compose deltas -- done here to avoid aliasing when calling with `d1` and `sum` pointing to the same variable
+    compose(d1, d2, dt, sum);
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, typename D6, typename D7, typename D8, typename D9, class T>
+inline void between(const MatrixBase<D1>& dp1, const QuaternionBase<D2>& dq1, const MatrixBase<D3>& dv1,
+                    const MatrixBase<D4>& dp2, const QuaternionBase<D5>& dq2, const MatrixBase<D6>& dv2,
+                    const T dt,
+                    MatrixBase<D7>& diff_p, QuaternionBase<D8>& diff_q, MatrixBase<D9>& diff_v )
+{
+        MatrixSizeCheck<3, 1>::check(dp1);
+        MatrixSizeCheck<3, 1>::check(dv1);
+        MatrixSizeCheck<3, 1>::check(dp2);
+        MatrixSizeCheck<3, 1>::check(dv2);
+        MatrixSizeCheck<3, 1>::check(diff_p);
+        MatrixSizeCheck<3, 1>::check(diff_v);
+
+        diff_p = dq1.conjugate() * ( dp2 - dp1 - dv1*dt );
+        diff_q = dq1.conjugate() *   dq2;
+        diff_v = dq1.conjugate() * ( dv2 - dv1 );
+}
+
+template<typename D1, typename D2, typename D3, class T>
+inline void between(const MatrixBase<D1>& d1,
+                    const MatrixBase<D2>& d2,
+                    T dt,
+                    MatrixBase<D3>& d2_minus_d1)
+{
+    MatrixSizeCheck<10, 1>::check(d1);
+    MatrixSizeCheck<10, 1>::check(d2);
+    MatrixSizeCheck<10, 1>::check(d2_minus_d1);
+
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dp1    ( & d1(0) );
+    Map<const Quaternion<typename D1::Scalar> >     dq1    ( & d1(3) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dv1    ( & d1(7) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dp2    ( & d2(0) );
+    Map<const Quaternion<typename D2::Scalar> >     dq2    ( & d2(3) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dv2    ( & d2(7) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         diff_p ( & d2_minus_d1(0) );
+    Map<Quaternion<typename D3::Scalar> >           diff_q ( & d2_minus_d1(3) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         diff_v ( & d2_minus_d1(7) );
+
+    between(dp1, dq1, dv1, dp2, dq2, dv2, dt, diff_p, diff_q, diff_v);
+}
+
+template<typename D1, typename D2, class T>
+inline Matrix<typename D1::Scalar, 10, 1> between(const MatrixBase<D1>& d1,
+                                                  const MatrixBase<D2>& d2,
+                                                  T dt)
+{
+    Matrix<typename D1::Scalar, 10, 1> diff;
+    between(d1, d2, dt, diff);
+    return diff;
+}
+
+template<typename D1, typename D2, typename D3, class T>
+inline void composeOverState(const MatrixBase<D1>& x,
+                             const MatrixBase<D2>& d,
+                             T dt,
+                             MatrixBase<D3>& x_plus_d)
+{
+    MatrixSizeCheck<10, 1>::check(x);
+    MatrixSizeCheck<10, 1>::check(d);
+    MatrixSizeCheck<10, 1>::check(x_plus_d);
+
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   p         ( & x( 0 ) );
+    Map<const Quaternion<typename D1::Scalar> >     q         ( & x( 3 ) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   v         ( & x( 7 ) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dp        ( & d( 0 ) );
+    Map<const Quaternion<typename D2::Scalar> >     dq        ( & d( 3 ) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dv        ( & d( 7 ) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         p_plus_d  ( & x_plus_d( 0 ) );
+    Map<Quaternion<typename D3::Scalar> >           q_plus_d  ( & x_plus_d( 3 ) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         v_plus_d  ( & x_plus_d( 7 ) );
+
+    p_plus_d = p + v*dt + 0.5*gravity()*dt*dt + q*dp;
+    v_plus_d = v +            gravity()*dt    + q*dv;
+    q_plus_d =                                  q*dq; // dq here to avoid possible aliasing between x and x_plus_d
+}
+
+template<typename D1, typename D2, class T>
+inline Matrix<typename D1::Scalar, 10, 1> composeOverState(const MatrixBase<D1>& x,
+                                                           const MatrixBase<D2>& d,
+                                                           T dt)
+{
+    Matrix<typename D1::Scalar, 10, 1>  ret;
+    composeOverState(x, d, dt, ret);
+    return ret;
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, typename D6, typename D7, typename D8, typename D9, class T>
+inline void betweenStates(const MatrixBase<D1>& p1, const QuaternionBase<D2>& q1, const MatrixBase<D3>& v1,
+                          const MatrixBase<D4>& p2, const QuaternionBase<D5>& q2, const MatrixBase<D6>& v2,
+                          const T dt,
+                          MatrixBase<D7>& dp, QuaternionBase<D8>& dq, MatrixBase<D9>& dv )
+{
+        MatrixSizeCheck<3, 1>::check(p1);
+        MatrixSizeCheck<3, 1>::check(v1);
+        MatrixSizeCheck<3, 1>::check(p2);
+        MatrixSizeCheck<3, 1>::check(v2);
+        MatrixSizeCheck<3, 1>::check(dp);
+        MatrixSizeCheck<3, 1>::check(dv);
+
+        dp = q1.conjugate() * ( p2 - p1 - v1*dt - 0.5*gravity()*dt*dt );
+        dq = q1.conjugate() *   q2;
+        dv = q1.conjugate() * ( v2 - v1         -     gravity()*dt );
+}
+
+template<typename D1, typename D2, typename D3, class T>
+inline void betweenStates(const MatrixBase<D1>& x1,
+                          const MatrixBase<D2>& x2,
+                          T dt,
+                          MatrixBase<D3>& x2_minus_x1)
+{
+    MatrixSizeCheck<10, 1>::check(x1);
+    MatrixSizeCheck<10, 1>::check(x2);
+    MatrixSizeCheck<10, 1>::check(x2_minus_x1);
+
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   p1  ( & x1(0) );
+    Map<const Quaternion<typename D1::Scalar> >     q1  ( & x1(3) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   v1  ( & x1(7) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   p2  ( & x2(0) );
+    Map<const Quaternion<typename D2::Scalar> >     q2  ( & x2(3) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   v2  ( & x2(7) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         dp  ( & x2_minus_x1(0) );
+    Map<Quaternion<typename D3::Scalar> >           dq  ( & x2_minus_x1(3) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         dv  ( & x2_minus_x1(7) );
+
+    betweenStates(p1, q1, v1, p2, q2, v2, dt, dp, dq, dv);
+}
+
+template<typename D1, typename D2, class T>
+inline Matrix<typename D1::Scalar, 10, 1> betweenStates(const MatrixBase<D1>& x1,
+                                                        const MatrixBase<D2>& x2,
+                                                        T dt)
+{
+    Matrix<typename D1::Scalar, 10, 1> ret;
+    betweenStates(x1, x2, dt, ret);
+    return ret;
+}
+
+template<typename Derived>
+Matrix<typename Derived::Scalar, 9, 1> lift(const MatrixBase<Derived>& delta_in)
+{
+    MatrixSizeCheck<10, 1>::check(delta_in);
+
+    Matrix<typename Derived::Scalar, 9, 1> ret;
+
+    Map<const Matrix<typename Derived::Scalar, 3, 1> >   dp_in  ( & delta_in(0) );
+    Map<const Quaternion<typename Derived::Scalar> >     dq_in  ( & delta_in(3) );
+    Map<const Matrix<typename Derived::Scalar, 3, 1> >   dv_in  ( & delta_in(7) );
+    Map<Matrix<typename Derived::Scalar, 3, 1> >         dp_ret ( & ret(0) );
+    Map<Matrix<typename Derived::Scalar, 3, 1> >         do_ret ( & ret(3) );
+    Map<Matrix<typename Derived::Scalar, 3, 1> >         dv_ret ( & ret(6) );
+
+    dp_ret = dp_in;
+    do_ret = log_q(dq_in);
+    dv_ret = dv_in;
+
+    return ret;
+}
+
+template<typename Derived>
+Matrix<typename Derived::Scalar, 10, 1> retract(const MatrixBase<Derived>& d_in)
+{
+    MatrixSizeCheck<9, 1>::check(d_in);
+
+    Matrix<typename Derived::Scalar, 10, 1> ret;
+
+    Map<const Matrix<typename Derived::Scalar, 3, 1> >   dp_in  ( & d_in(0) );
+    Map<const Matrix<typename Derived::Scalar, 3, 1> >   do_in  ( & d_in(3) );
+    Map<const Matrix<typename Derived::Scalar, 3, 1> >   dv_in  ( & d_in(6) );
+    Map<Matrix<typename Derived::Scalar, 3, 1> >         dp     ( &  ret(0) );
+    Map<Quaternion<typename Derived::Scalar> >           dq     ( &  ret(3) );
+    Map<Matrix<typename Derived::Scalar, 3, 1> >         dv     ( &  ret(7) );
+
+    dp = dp_in;
+    dq = exp_q(do_in);
+    dv = dv_in;
+
+    return ret;
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, typename D6, typename D7, typename D8, typename D9>
+inline void plus(const MatrixBase<D1>& dp1, const QuaternionBase<D2>& dq1, const MatrixBase<D3>& dv1,
+                 const MatrixBase<D4>& dp2, const MatrixBase<D5>& do2, const MatrixBase<D6>& dv2,
+                 MatrixBase<D7>& plus_p, QuaternionBase<D8>& plus_q, MatrixBase<D9>& plus_v )
+{
+        plus_p = dp1 + dp2;
+        plus_q = dq1 * exp_q(do2);
+        plus_v = dv1 + dv2;
+}
+
+template<typename D1, typename D2, typename D3>
+inline void plus(const MatrixBase<D1>& d1,
+                 const MatrixBase<D2>& d2,
+                 MatrixBase<D3>& d_pert)
+{
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dp1    ( & d1(0) );
+    Map<const Quaternion<typename D1::Scalar> >     dq1    ( & d1(3) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dv1    ( & d1(7) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dp2    ( & d2(0) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   do2    ( & d2(3) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dv2    ( & d2(6) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         dp_p ( & d_pert(0) );
+    Map<Quaternion<typename D3::Scalar> >           dq_p ( & d_pert(3) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         dv_p ( & d_pert(7) );
+
+    plus(dp1, dq1, dv1, dp2, do2, dv2, dp_p, dq_p, dv_p);
+}
+
+template<typename D1, typename D2>
+inline Matrix<typename D1::Scalar, 10, 1> plus(const MatrixBase<D1>& d1,
+                                               const MatrixBase<D2>& d2)
+{
+    Matrix<typename D1::Scalar, 10, 1> ret;
+    plus(d1, d2, ret);
+    return ret;
+}
+
+template<typename D1, typename D2, typename D3, typename D4, typename D5, typename D6, typename D7, typename D8, typename D9>
+inline void diff(const MatrixBase<D1>& dp1, const QuaternionBase<D2>& dq1, const MatrixBase<D3>& dv1,
+                 const MatrixBase<D4>& dp2, const QuaternionBase<D5>& dq2, const MatrixBase<D6>& dv2,
+                 MatrixBase<D7>& diff_p, MatrixBase<D8>& diff_o, MatrixBase<D9>& diff_v )
+{
+        diff_p = dp2 - dp1;
+        diff_o = log_q(dq1.conjugate() * dq2);
+        diff_v = dv2 - dv1;
+}
+
+
+template<typename D1, typename D2, typename D3>
+inline void diff(const MatrixBase<D1>& d1,
+                 const MatrixBase<D2>& d2,
+                 MatrixBase<D3>& err)
+{
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dp1    ( & d1(0) );
+    Map<const Quaternion<typename D1::Scalar> >     dq1    ( & d1(3) );
+    Map<const Matrix<typename D1::Scalar, 3, 1> >   dv1    ( & d1(7) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dp2    ( & d2(0) );
+    Map<const Quaternion<typename D2::Scalar> >     dq2    ( & d2(3) );
+    Map<const Matrix<typename D2::Scalar, 3, 1> >   dv2    ( & d2(7) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         diff_p ( & err(0) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         diff_o ( & err(3) );
+    Map<Matrix<typename D3::Scalar, 3, 1> >         diff_v ( & err(6) );
+
+    diff(dp1, dq1, dv1, dp2, dq2, dv2, diff_p, diff_o, diff_v);
+}
+
+template<typename D1, typename D2>
+inline Matrix<typename D1::Scalar, 9, 1> diff(const MatrixBase<D1>& d1,
+                                              const MatrixBase<D2>& d2)
+{
+    Matrix<typename D1::Scalar, 9, 1> ret;
+    diff(d1, d2, ret);
+    return ret;
+}
+
+
+} // namespace imu
+} // namespace wolf
+
+#endif /* IMU_TOOLS_H_ */
diff --git a/src/landmark_polyline_2D.cpp b/src/landmark_polyline_2D.cpp
index 71111ff6a895736a2adfbe6138354ba70b7b8636..e0f2a6cfbf12b13af7bfe291f08d7a5848dfd60d 100644
--- a/src/landmark_polyline_2D.cpp
+++ b/src/landmark_polyline_2D.cpp
@@ -248,6 +248,7 @@ void LandmarkPolyline2D::mergePoints(int _remove_id, int _remain_id)
             if (ctr_point_ptr->getLandmarkPointId() == _remove_id)
                 new_ctr_ptr = std::make_shared<ConstraintPoint2D>(std::static_pointer_cast<FeaturePolyline2D>(ctr_ptr->getFeaturePtr()),
                                                                   std::static_pointer_cast<LandmarkPolyline2D>(shared_from_this()),
+                                                                  ctr_point_ptr->getProcessor(),
                                                                   ctr_point_ptr->getFeaturePointId(),
                                                                   _remain_id,
                                                                   ctr_point_ptr->getApplyLossFunction(),
@@ -261,6 +262,7 @@ void LandmarkPolyline2D::mergePoints(int _remove_id, int _remain_id)
             if (ctr_point_ptr->getLandmarkPointId() == _remove_id)
                 new_ctr_ptr = std::make_shared<ConstraintPointToLine2D>(std::static_pointer_cast<FeaturePolyline2D>(ctr_ptr->getFeaturePtr()),
                                                                         std::static_pointer_cast<LandmarkPolyline2D>(shared_from_this()),
+                                                                        ctr_point_ptr->getProcessor(),
                                                                         ctr_point_ptr->getFeaturePointId(),
                                                                         _remain_id,
                                                                         ctr_point_ptr->getLandmarkPointAuxId(),
@@ -270,6 +272,7 @@ void LandmarkPolyline2D::mergePoints(int _remove_id, int _remain_id)
             else if (ctr_point_ptr->getLandmarkPointAuxId() == _remove_id)
                 new_ctr_ptr = std::make_shared<ConstraintPointToLine2D>(std::static_pointer_cast<FeaturePolyline2D>(ctr_ptr->getFeaturePtr()),
                                                                         std::static_pointer_cast<LandmarkPolyline2D>(shared_from_this()),
+                                                                        ctr_point_ptr->getProcessor(),
                                                                         ctr_point_ptr->getFeaturePointId(),
                                                                         ctr_point_ptr->getLandmarkPointId(),
                                                                         _remain_id,
@@ -386,7 +389,7 @@ YAML::Node LandmarkPolyline2D::saveToYaml() const
 // Register landmark creator
 namespace
 {
-const bool registered_lmk_polyline_2D = LandmarkFactory::get().registerCreator("POLYLINE 2D", LandmarkPolyline2D::create);
+const bool WOLF_UNUSED registered_lmk_polyline_2D = LandmarkFactory::get().registerCreator("POLYLINE 2D", LandmarkPolyline2D::create);
 }
 
 } /* namespace wolf */
diff --git a/src/motion_buffer.cpp b/src/motion_buffer.cpp
index 9bb43a8f59276bc498a21637d4dc0ae47026e909..1ac2318b9c757b466c101fcc5d7b9833c507d595 100644
--- a/src/motion_buffer.cpp
+++ b/src/motion_buffer.cpp
@@ -2,54 +2,65 @@
 namespace wolf
 {
 
-Motion::Motion():
-        ts_(0)
-{
-    resize(0);
-}
-
-Motion::Motion(const TimeStamp& _ts, const VectorXs& _delta, const VectorXs& _delta_int, const MatrixXs& _jac_delta, const MatrixXs& _jac_delta_int, const MatrixXs& _delta_cov) :
+Motion::Motion(const TimeStamp& _ts,
+               const VectorXs& _data,
+               const MatrixXs& _data_cov,
+               const VectorXs& _delta,
+               const MatrixXs& _delta_cov,
+               const VectorXs& _delta_integr,
+               const MatrixXs& _delta_integr_cov,
+               const MatrixXs& _jac_delta,
+               const MatrixXs& _jac_delta_int,
+               const MatrixXs& _jac_calib) :
+        data_size_(_data.size()),
         delta_size_(_delta.size()),
-        cov_size_(_delta_cov.size()),
+        cov_size_(_delta_cov.cols()),
+        calib_size_(_jac_calib.cols()),
         ts_(_ts),
+        data_(_data),
+        data_cov_(_data_cov),
         delta_(_delta),
-        delta_integr_(_delta_int),
+        delta_cov_(_delta_cov),
+        delta_integr_(_delta_integr),
+        delta_integr_cov_(_delta_integr_cov),
         jacobian_delta_(_jac_delta),
         jacobian_delta_integr_(_jac_delta_int),
-        delta_cov_(_delta_cov)
+        jacobian_calib_(_jac_calib)
 {
 }
 
-Motion::Motion(const TimeStamp& _ts, Size _delta_size, Size _cov_size) :
+Motion::Motion(const TimeStamp& _ts, Size _data_size, Size _delta_size, Size _cov_size, Size _calib_size) :
+        data_size_(_data_size),
+        delta_size_(_delta_size),
+        cov_size_(_cov_size),
+        calib_size_(_calib_size),
         ts_(_ts)
 {
-    resize(_delta_size, _cov_size == 0 ? _delta_size : _cov_size);
+    resize(_data_size, _delta_size, _cov_size, _calib_size);
 }
 
 Motion::~Motion()
 {
 }
 
-void Motion::resize(Size ds)
+void Motion::resize(Size _data_s, Size _delta_s, Size _delta_cov_s, Size _calib_s)
 {
-    resize(ds, ds);
-}
-
-void Motion::resize(Size ds, Size dcs)
-{
-    delta_.resize(ds);
-    delta_integr_.resize(ds);
-    jacobian_delta_.resize(dcs, dcs);
-    jacobian_delta_integr_.resize(dcs, dcs);
-    delta_cov_.resize(dcs, dcs);
-//    delta_integr_cov_.resize(dcs, dcs);
+    data_.resize(_data_s);
+    data_cov_.resize(_data_s, _data_s);
+    delta_.resize(_delta_s);
+    delta_cov_.resize(_delta_cov_s, _delta_cov_s);
+    delta_integr_.resize(_delta_s);
+    delta_integr_cov_.resize(_delta_cov_s, _delta_cov_s);
+    jacobian_delta_.resize(_delta_cov_s, _delta_cov_s);
+    jacobian_delta_integr_.resize(_delta_cov_s, _delta_cov_s);
+    jacobian_calib_.resize(_delta_cov_s, _calib_s);
 }
 
 
 ////////////////////////////////////////////////////////////////////////////////////////
 
-MotionBuffer::MotionBuffer(Size _delta_size, Size _cov_size) :
-        delta_size_(_delta_size), cov_size_(_cov_size)
+MotionBuffer::MotionBuffer(Size _data_size, Size _delta_size, Size _cov_size, Size _calib_size) :
+        data_size_(_data_size), delta_size_(_delta_size), cov_size_(_cov_size), calib_size_(_calib_size)
 {
 }
 
@@ -106,29 +117,29 @@ void MotionBuffer::split(const TimeStamp& _ts, MotionBuffer& _buffer_part_before
 
 MatrixXs MotionBuffer::integrateCovariance() const
 {
-    Eigen::MatrixXs cov(cov_size_, cov_size_);
-    cov.setZero();
+    Eigen::MatrixXs delta_integr_cov(cov_size_, cov_size_);
+    delta_integr_cov.setZero();
     for (Motion mot : container_)
     {
-        cov = mot.jacobian_delta_integr_ * cov * mot.jacobian_delta_integr_.transpose()
-                + mot.jacobian_delta_ * mot.delta_cov_ * mot.jacobian_delta_.transpose();
+        delta_integr_cov = mot.jacobian_delta_integr_ * delta_integr_cov * mot.jacobian_delta_integr_.transpose()
+                         + mot.jacobian_delta_        * mot.delta_cov_   * mot.jacobian_delta_.transpose();
     }
-    return cov;
+    return delta_integr_cov;
 }
 
 MatrixXs MotionBuffer::integrateCovariance(const TimeStamp& _ts) const
 {
-    Eigen::MatrixXs cov(cov_size_, cov_size_);
-    cov.setZero();
+    Eigen::MatrixXs delta_integr_cov(cov_size_, cov_size_);
+    delta_integr_cov.setZero();
     for (Motion mot : container_)
     {
         if (mot.ts_ > _ts)
             break;
 
-        cov = mot.jacobian_delta_integr_ * cov * mot.jacobian_delta_integr_.transpose()
-                + mot.jacobian_delta_ * mot.delta_cov_ * mot.jacobian_delta_.transpose();
+        delta_integr_cov = mot.jacobian_delta_integr_ * delta_integr_cov * mot.jacobian_delta_integr_.transpose()
+                         + mot.jacobian_delta_        * mot.delta_cov_   * mot.jacobian_delta_.transpose();
     }
-    return cov;
+    return delta_integr_cov;
 }
 
 MatrixXs MotionBuffer::integrateCovariance(const TimeStamp& _ts_1, const TimeStamp _ts_2) const
@@ -147,12 +158,12 @@ MatrixXs MotionBuffer::integrateCovariance(const TimeStamp& _ts_1, const TimeSta
     return cov;
 }
 
-void MotionBuffer::print(bool show_delta, bool show_delta_cov, bool show_delta_int, bool show_delta_int_cov)
+void MotionBuffer::print(bool show_data, bool show_delta, bool show_delta_int, bool show_jacs)
 {
     using std::cout;
     using std::endl;
 
-    if (!show_delta && !show_delta_cov && !show_delta_int && !show_delta_int_cov)
+    if (!show_data && !show_delta && !show_delta_int && !show_jacs)
     {
         cout << "Buffer state [" << container_.size() << "] : <";
         for (Motion mot : container_)
@@ -167,14 +178,28 @@ void MotionBuffer::print(bool show_delta, bool show_delta_cov, bool show_delta_i
             cout << "-- Motion (" << mot.ts_ << ")" << endl;
 //            if (show_ts)
 //                cout << "   ts: " << mot.ts_ << endl;
+            if (show_data)
+            {
+                cout << "   data: " << mot.data_.transpose() << endl;
+                cout << "   data cov: \n" << mot.data_cov_ << endl;
+            }
             if (show_delta)
+            {
                 cout << "   delta: " << mot.delta_.transpose() << endl;
-            if (show_delta_cov)
                 cout << "   delta cov: \n" << mot.delta_cov_ << endl;
+            }
             if (show_delta_int)
+            {
                 cout << "   delta integrated: " << mot.delta_integr_.transpose() << endl;
-            if (show_delta_int_cov)
-                cout << "   delta integrated cov: \n" << integrateCovariance(mot.ts_) << endl;
+                cout << "   delta integrated cov: \n" << mot.delta_integr_cov_ << endl;
+            }
+            if (show_jacs)
+            {
+                cout << "   Jac delta: \n" << mot.jacobian_delta_ << endl;
+                cout << "   Jac delta integr: \n" << mot.jacobian_delta_integr_ << endl;
+                cout << "   Jac calib: \n" << mot.jacobian_calib_ << endl;
+
+            }
         }
     }
 }
diff --git a/src/motion_buffer.h b/src/motion_buffer.h
index cc0c94ab482930331d9131e5a6addf79600c07bc..5bd1d3d5e729cbb89a28e88f1935be16c71b0b65 100644
--- a/src/motion_buffer.h
+++ b/src/motion_buffer.h
@@ -21,22 +21,32 @@ using namespace Eigen;
 struct Motion
 {
     public:
-        Size delta_size_, cov_size_;
+        Size data_size_, delta_size_, cov_size_, calib_size_;
         TimeStamp ts_;                          ///< Time stamp
+        Eigen::VectorXs data_;                  ///< instantaneous motion data
+        Eigen::MatrixXs data_cov_;              ///< covariance of the instantaneous data
         Eigen::VectorXs delta_;                 ///< instantaneous motion delta
+        Eigen::MatrixXs delta_cov_;             ///< covariance of the instantaneous delta
         Eigen::VectorXs delta_integr_;          ///< the integrated motion or delta-integral
+        Eigen::MatrixXs delta_integr_cov_;      ///< covariance of the integrated delta
         Eigen::MatrixXs jacobian_delta_;        ///< Jacobian of the integration wrt delta_
         Eigen::MatrixXs jacobian_delta_integr_; ///< Jacobian of the integration wrt delta_integr_
-        Eigen::MatrixXs delta_cov_;             ///< covariance of the instantaneous delta
-//        Eigen::MatrixXs delta_integr_cov_;      ///< covariance of the integrated delta
+        Eigen::MatrixXs jacobian_calib_;        ///< Jacobian of delta_integr wrt extra states (TBD by the derived processors)
     public:
-        Motion();
-        Motion(const TimeStamp& _ts, Size _delta_size = 0, Size _cov_size = 0);
-//        Motion(const TimeStamp& _ts, const VectorXs& _delta, const VectorXs& _delta_int, Size _cov_size);
-        Motion(const TimeStamp& _ts, const VectorXs& _delta, const VectorXs& _delta_int, const MatrixXs& _jac_delta, const MatrixXs& _jac_delta_int, const MatrixXs& _delta_cov);
+        Motion() = delete; // completely delete unpredictable stuff like this
+        Motion(const TimeStamp& _ts, Size _data_size, Size _delta_size, Size _cov_size, Size _calib_size);
+        Motion(const TimeStamp& _ts,
+               const VectorXs& _data,
+               const MatrixXs& _data_cov,
+               const VectorXs& _delta,
+               const MatrixXs& _delta_cov,
+               const VectorXs& _delta_int,
+               const MatrixXs& _delta_integr_cov,
+               const MatrixXs& _jac_delta,
+               const MatrixXs& _jac_delta_int,
+               const MatrixXs& _jacobian_calib);// = MatrixXs::Zero(0,0));
         ~Motion();
-        void resize(Size ds, Size dcs);
-        void resize(Size ds);
+        void resize(Size _data_s, Size _delta_s, Size _delta_cov_s, Size _calib_s);
 
 }; ///< One instance of the buffered data, corresponding to a particular time stamp.
 
@@ -64,8 +74,9 @@ struct Motion
  */
 class MotionBuffer{
     public:
-        Size delta_size_, cov_size_;
-        MotionBuffer(Size _delta_size, Size _cov_size);
+        Size data_size_, delta_size_, cov_size_, calib_size_;
+        MotionBuffer() = delete;
+        MotionBuffer(Size _data_size, Size _delta_size, Size _cov_size, Size _calib_size);
         std::list<Motion>& get();
         const std::list<Motion>& get() const;
         const Motion& getMotion(const TimeStamp& _ts) const;
@@ -76,7 +87,7 @@ class MotionBuffer{
         MatrixXs integrateCovariance() const; // Integrate all buffer
         MatrixXs integrateCovariance(const TimeStamp& _ts) const; // Integrate up to time stamp (included)
         MatrixXs integrateCovariance(const TimeStamp& _ts_1, const TimeStamp _ts_2) const; // integrate between time stamps (both included)
-        void print(bool show_delta = 0, bool show_delta_cov = 0, bool show_delta_int = 0, bool show_delta_int_cov = 0);
+        void print(bool show_data = 0, bool show_delta = 0, bool show_delta_int = 0, bool show_jacs = 0);
 
     private:
         std::list<Motion> container_;
diff --git a/src/problem.cpp b/src/problem.cpp
index c1bc34fa8b0b541dfb8fed4388553051f8b3adce..080e392fe4647a0f608ba8b002ff5a932402f041 100644
--- a/src/problem.cpp
+++ b/src/problem.cpp
@@ -91,6 +91,13 @@ ProcessorBasePtr Problem::installProcessor(const std::string& _prc_type, //
                                          SensorBasePtr _corresponding_sensor_ptr, //
                                          ProcessorParamsBasePtr _prc_params)
 {
+    if (_corresponding_sensor_ptr == nullptr)
+    {
+      WOLF_ERROR("Cannot install processor '", _unique_processor_name,
+                 "' since the associated sensor does not exist !");
+      return ProcessorBasePtr();
+    }
+
     ProcessorBasePtr prc_ptr = ProcessorFactory::get().create(uppercase(_prc_type), _unique_processor_name, _prc_params, _corresponding_sensor_ptr);
     _corresponding_sensor_ptr->addProcessor(prc_ptr);
 
@@ -300,7 +307,7 @@ void Problem::getFrameStructureSize(Size& _x_size, Size& _cov_size) const
     else if (trajectory_ptr_->getFrameStructure() == "POV 3D")
     {
         _x_size = 10;
-        _cov_size = 10;
+        _cov_size = 9;
     }
     else if (trajectory_ptr_->getFrameStructure() == "PQVBB 3D")
     {
@@ -413,7 +420,6 @@ void Problem::removeConstraintPtr(ConstraintBasePtr _constraint_ptr)
     // Remove addition notification
     if (ctr_notif_it != constraint_notification_list_.end())
         constraint_notification_list_.erase(ctr_notif_it); // CHECKED shared_ptr is not active after erase
-
     // Add remove notification
     else
         constraint_notification_list_.push_back(ConstraintNotification({REMOVE, _constraint_ptr}));
@@ -499,6 +505,11 @@ bool Problem::getCovarianceBlock(std::map<StateBlockPtr, unsigned int> _sb_2_idx
     return true;
 }
 
+bool Problem::getCovarianceBlock(StateBlockPtr _state, Eigen::MatrixXs& _cov, const int _row_and_col)
+{
+    return getCovarianceBlock(_state, _state, _cov, _row_and_col, _row_and_col);
+}
+
 bool Problem::getFrameCovariance(FrameBasePtr _frame_ptr, Eigen::MatrixXs& _covariance)
 {
 //    return getCovarianceBlock(_frame_ptr->getPPtr(), _frame_ptr->getPPtr(), _covariance, 0,                                0                               ) &&
@@ -510,12 +521,12 @@ bool Problem::getFrameCovariance(FrameBasePtr _frame_ptr, Eigen::MatrixXs& _cova
     bool success(true);
     int i = 0, j = 0;
 
-    for (auto sb_i : _frame_ptr->getStateBlockVec())
+    for (const auto& sb_i : _frame_ptr->getStateBlockVec())
     {
         if (sb_i)
         {
             j = 0;
-            for (auto sb_j : _frame_ptr->getStateBlockVec())
+            for (const auto& sb_j : _frame_ptr->getStateBlockVec())
             {
                 if (sb_j)
                 {
@@ -532,7 +543,7 @@ bool Problem::getFrameCovariance(FrameBasePtr _frame_ptr, Eigen::MatrixXs& _cova
 Eigen::MatrixXs Problem::getFrameCovariance(FrameBasePtr _frame_ptr)
 {
     Size sz = 0;
-    for (auto sb : _frame_ptr->getStateBlockVec())
+    for (const auto& sb : _frame_ptr->getStateBlockVec())
         if (sb)
             sz += sb->getSize();
     Eigen::MatrixXs covariance(sz, sz);
@@ -603,7 +614,13 @@ FrameBasePtr Problem::setPrior(const Eigen::VectorXs& _prior_state, const Eigen:
         FrameBasePtr origin_frame_ptr = emplaceFrame(KEY_FRAME, _prior_state, _ts);
 
         // create origin capture with the given state as data
-        CaptureFixPtr init_capture = std::make_shared<CaptureFix>(_ts, nullptr, _prior_state, _prior_cov);
+        // Capture fix only takes 3D position and Quaternion orientation
+        CaptureFixPtr init_capture;
+        if ((trajectory_ptr_->getFrameStructure() == "PQVBB 3D") || (trajectory_ptr_->getFrameStructure() == "POV 3D") )
+            init_capture = std::make_shared<CaptureFix>(_ts, nullptr, _prior_state.head(7), _prior_cov);
+        else
+            init_capture = std::make_shared<CaptureFix>(_ts, nullptr, _prior_state, _prior_cov);
+
         origin_frame_ptr->addCapture(init_capture);
 
         // emplace feature and constraint
diff --git a/src/problem.h b/src/problem.h
index 796a37dca8087c10618070cd1538300c5ca827f8..48b68ed6452ab76ec739dc834a922472fb55d069 100644
--- a/src/problem.h
+++ b/src/problem.h
@@ -245,6 +245,7 @@ class Problem : public std::enable_shared_from_this<Problem>
         void addCovarianceBlock(StateBlockPtr _state1, StateBlockPtr _state2, const Eigen::MatrixXs& _cov);
         bool getCovarianceBlock(StateBlockPtr _state1, StateBlockPtr _state2, Eigen::MatrixXs& _cov, const int _row = 0, const int _col=0);
         bool getCovarianceBlock(std::map<StateBlockPtr, unsigned int> _sb_2_idx, Eigen::MatrixXs& _cov);
+        bool getCovarianceBlock(StateBlockPtr _state, Eigen::MatrixXs& _cov, const int _row_and_col = 0);
         bool getFrameCovariance(FrameBasePtr _frame_ptr, Eigen::MatrixXs& _covariance);
         Eigen::MatrixXs getFrameCovariance(FrameBasePtr _frame_ptr);
         Eigen::MatrixXs getLastKeyFrameCovariance();
diff --git a/src/processor_base.h b/src/processor_base.h
index fb828e8c4cadffd926dc5fa971e321302d80610d..f87df2394d54ad7abf44637d971fa550b857968a 100644
--- a/src/processor_base.h
+++ b/src/processor_base.h
@@ -23,8 +23,11 @@ namespace wolf {
  */
 struct ProcessorParamsBase
 {
-        std::string type;
-        std::string name;
+    ProcessorParamsBase()          = default;
+    virtual ~ProcessorParamsBase() = default;
+
+    std::string type;
+    std::string name;
 };
 
 //class ProcessorBase
@@ -33,8 +36,8 @@ class ProcessorBase : public NodeBase, public std::enable_shared_from_this<Proce
     private:
         SensorBaseWPtr sensor_ptr_;
 
-        static unsigned int processor_id_count_;
         bool is_removing_; ///< A flag for safely removing nodes from the Wolf tree. See remove().
+        static unsigned int processor_id_count_;
 
     public:
         ProcessorBase(const std::string& _type, const Scalar& _time_tolerance = 0);
diff --git a/src/processor_factory.h b/src/processor_factory.h
index a5ba731188daa54b33806d1c8bbdb4cc91c22efb..00d2d50f6bfdc5605b3890ed6f49a2ca38023ba7 100644
--- a/src/processor_factory.h
+++ b/src/processor_factory.h
@@ -177,8 +177,8 @@ inline std::string ProcessorFactory::getClass()
 
 
 #define WOLF_REGISTER_PROCESSOR(ProcessorType, ProcessorName) \
-  namespace{ const bool ProcessorName##Registered = \
-    ProcessorFactory::get().registerCreator(ProcessorType, ProcessorName::create); }\
+  namespace{ const bool WOLF_UNUSED ProcessorName##Registered = \
+    wolf::ProcessorFactory::get().registerCreator(ProcessorType, ProcessorName::create); }\
 
 } /* namespace wolf */
 
diff --git a/src/processor_image_feature.h b/src/processor_image_feature.h
index a8f1a1c4b092022350424a41194659fc41a00172..ac1e5786d4c7961cbbf41db32633b5bf2e7866f7 100644
--- a/src/processor_image_feature.h
+++ b/src/processor_image_feature.h
@@ -185,7 +185,7 @@ inline bool ProcessorImageFeature::voteForKeyFrame()
 
 inline ConstraintBasePtr ProcessorImageFeature::createConstraint(FeatureBasePtr _feature_ptr, FeatureBasePtr _feature_other_ptr)
 {
-    ConstraintEpipolarPtr const_epipolar_ptr = std::make_shared<ConstraintEpipolar>(_feature_ptr, _feature_other_ptr);
+    ConstraintEpipolarPtr const_epipolar_ptr = std::make_shared<ConstraintEpipolar>(_feature_ptr, _feature_other_ptr, shared_from_this());
 //    _feature_ptr->addConstraint(const_epipolar_ptr);
 //    _feature_other_ptr->addConstrainedBy(const_epipolar_ptr);
     return const_epipolar_ptr;
diff --git a/src/processor_image_landmark.cpp b/src/processor_image_landmark.cpp
index 0c060b034bd326521e0a85971b8965615d24db50..ff9136c351250ba4e6ef72957adb9f5d82adc045 100644
--- a/src/processor_image_landmark.cpp
+++ b/src/processor_image_landmark.cpp
@@ -292,7 +292,7 @@ ConstraintBasePtr ProcessorImageLandmark::createConstraint(FeatureBasePtr _featu
 
         LandmarkAHPPtr landmark_ahp = std::static_pointer_cast<LandmarkAHP>(_landmark_ptr);
 
-        ConstraintAHPPtr constraint_ptr = ConstraintAHP::create(_feature_ptr, landmark_ahp, true);
+        ConstraintAHPPtr constraint_ptr = ConstraintAHP::create(_feature_ptr, landmark_ahp, shared_from_this(), true);
 
         return constraint_ptr;
     }
diff --git a/src/processor_imu.cpp b/src/processor_imu.cpp
index 8afa310f325ad5d097778c86911066843bc41773..d4d9b78ee70ee2d0038046e35fa56feed40844ea 100644
--- a/src/processor_imu.cpp
+++ b/src/processor_imu.cpp
@@ -2,12 +2,17 @@
 
 namespace wolf {
 
-ProcessorIMU::ProcessorIMU() :
-        ProcessorMotion("IMU", 16, 10, 9, 6),
+ProcessorIMU::ProcessorIMU(ProcessorIMUParamsPtr _params) :
+        ProcessorMotion("IMU", 16, 10, 9, 6, 0.01, 6),
+        max_time_span_  (_params ? _params    ->max_time_span   : 1.0  ),
+        max_buff_length_(_params ? _params    ->max_buff_length : 10000   ),
+        dist_traveled_  (_params ? _params    ->dist_traveled   : 1.0  ),
+        angle_turned_   (_params ? _params    ->angle_turned    : 0.2  ),
+        voting_active_  (_params ? _params    ->voting_active    : false  ),
         frame_imu_ptr_(nullptr),
         gravity_(wolf::gravity()),
-        acc_bias_(Eigen::Vector3s::Zero()),
-        gyro_bias_(Eigen::Vector3s::Zero()),
+        acc_bias_(&calib_(0)),
+        gyro_bias_(&calib_(3)),
         acc_measured_(nullptr),
         gyro_measured_(nullptr),
         Dp_(nullptr), dp_(nullptr), Dp_out_(nullptr),
@@ -17,6 +22,7 @@ ProcessorIMU::ProcessorIMU() :
     // Set constant parts of Jacobians
     jacobian_delta_preint_.setIdentity(9,9);                                    // dDp'/dDp, dDv'/dDv, all zeros
     jacobian_delta_.setIdentity(9,9);                                           //
+    jacobian_calib_.setZero(9,6);
 }
 
 ProcessorIMU::~ProcessorIMU()
@@ -24,13 +30,203 @@ ProcessorIMU::~ProcessorIMU()
 //    std::cout << "destructed     -p-IMU" << id() << std::endl;
 }
 
-ProcessorBasePtr ProcessorIMU::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr)
+VectorXs ProcessorIMU::correctDelta(const Motion& _motion, const CaptureMotionPtr _capture)
 {
-    ProcessorIMUPtr prc_ptr = std::make_shared<ProcessorIMU>();
+
+    /* Correct measured delta: delta_corr = delta ++ J_bias * (bias - bias_preint)
+     * where:
+     *   delta       = pre-integrated delta at time dt
+     *   J_bias      = Jacobian of the preintegrated delta at time dt
+     *   bias        = current bias estimate
+     *   bias_preint = bias estimate when we performed the pre-integration
+     *   ++          = additive composition: x+dx for p and v, q*exp(dv) for the quaternion.
+     */
+
+    // Get current delta and Jacobian
+    VectorXs delta_preint  = _motion.delta_integr_;
+    MatrixXs J_bias        = _motion.jacobian_calib_;
+
+    // Get current biases from the capture's origin frame
+    FrameIMUPtr frame_origin   = std::static_pointer_cast<FrameIMU>(_capture->getOriginFramePtr());
+    Vector6s bias; bias       << frame_origin->getAccBiasPtr()->getState(), frame_origin->getGyroBiasPtr()->getState();
+
+    // Get preintegrated biases from the capture's feature
+    FeatureIMUPtr feature              = std::static_pointer_cast<FeatureIMU>(_capture->getFeatureList().front());
+    Vector6s bias_preint; bias_preint << feature->acc_bias_preint_, feature->gyro_bias_preint_;
+
+    // Compute update step
+    VectorXs delta_step = J_bias * (bias - bias_preint);
+
+    // Correct delta
+    VectorXs delta_correct(10);
+    delta_correct.head(3)           = delta_preint.head(3) + delta_step.head(3);
+    Map<const Quaternions> deltaq   (&delta_preint(3));
+    Map<Quaternions> deltaq_correct (&delta_correct(3));
+    deltaq_correct                  = deltaq * v2q(delta_step.segment(3,3));
+    delta_correct.tail(3)           = delta_preint.tail(3) + delta_step.tail(3);
+
+    return delta_correct;
+}
+
+ProcessorBasePtr ProcessorIMU::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr _sen_ptr)
+{
+    // cast inputs to the correct type
+    std::shared_ptr<ProcessorIMUParams> prc_imu_params = std::static_pointer_cast<ProcessorIMUParams>(_params);
+
+    ProcessorIMUPtr prc_ptr = std::make_shared<ProcessorIMU>(prc_imu_params);
     prc_ptr->setName(_unique_name);
     return prc_ptr;
 }
 
+bool ProcessorIMU::voteForKeyFrame()
+{
+    //WOLF_DEBUG( "Time span   : " , getBuffer().get().back().ts_ - getBuffer().get().front().ts_ );
+    //WOLF_DEBUG( "BufferLength: " , getBuffer().get().size() );
+    //WOLF_DEBUG( "AngleTurned : " , 2.0 * acos(delta_integrated_(6)) );
+    if(!voting_active_)
+        return false;
+    // time span
+    if (getBuffer().get().back().ts_ - getBuffer().get().front().ts_ > max_time_span_)
+    {
+        WOLF_DEBUG( "PM: vote: time span" );
+        return true;
+    }
+    // buffer length
+    if (getBuffer().get().size() > max_buff_length_)
+    {
+        WOLF_DEBUG( "PM: vote: buffer size" );
+        return true;
+    }
+    /*// angle turned
+    Scalar angle = 2.0 * acos(delta_integrated_(6));
+    if (angle > angle_turned_)
+    {
+        WOLF_DEBUG( "PM: vote: angle turned" );
+        return true;
+    }*/
+    //WOLF_DEBUG( "PM: do not vote" );
+    return false;
+}
+
+Motion ProcessorIMU::interpolate(const Motion& _motion_ref, Motion& _motion_second, TimeStamp& _ts)
+{
+    /* Note: See extensive documentation in ProcessorMotion::interpolate().
+     *
+     * Interpolate between motion_ref and motion, as in:
+     *
+     *    motion_ref ------ ts_ ------ motion_sec
+     *                    return
+     *
+     * and return the motion at the given time_stamp ts_.
+     *
+     * DATA:
+     * Data receives no change
+     *
+     * DELTA:
+     * The delta's position and velocity receive linear interpolation:
+     *    p_ret = (ts - t_ref) / dt * (p - p_ref)
+     *    v_ret = (ts - t_ref) / dt * (v - v_ref)
+     *
+     * The delta's quaternion receives a slerp interpolation
+     *    q_ret = q_ref.slerp( (ts - t_ref) / dt , q);
+     *
+     * DELTA_INTEGR:
+     * The interpolated delta integral is just the reference integral plus the interpolated delta
+     *
+     * The second integral does not change
+     *
+     * Covariances receive linear interpolation
+     *    Q_ret = (ts - t_ref) / dt * Q_sec
+     */
+    // resolve out-of-bounds time stamp as if the time stamp was exactly on the bounds
+    if (_ts <= _motion_ref.ts_)    // behave as if _ts == _motion_ref.ts_
+    {
+        // return null motion. Second stays the same.
+        Motion motion_int     ( _motion_ref );
+        motion_int.data_      = _motion_second.data_;
+        motion_int.data_cov_  = _motion_second.data_cov_;
+        motion_int.delta_     = deltaZero();
+        motion_int.delta_cov_ . setZero();
+        return motion_int;
+    }
+    if (_motion_second.ts_ <= _ts)    // behave as if _ts == _motion_second.ts_
+    {
+        // return original second motion. Second motion becomes null motion
+        Motion motion_int         ( _motion_second );
+        _motion_second.delta_     = deltaZero();
+        _motion_second.delta_cov_ . setZero();
+        return motion_int;
+    }
+    assert(_motion_ref.ts_ <= _ts && "Interpolation time stamp out of bounds");
+    assert(_ts <= _motion_second.ts_ && "Interpolation time stamp out of bounds");
+
+    assert(_motion_ref.delta_.size() == delta_size_ && "Wrong delta size");
+    assert(_motion_ref.delta_cov_.cols() == delta_cov_size_ && "Wrong delta cov size");
+    assert(_motion_ref.delta_cov_.rows() == delta_cov_size_ && "Wrong delta cov size");
+    assert(_motion_ref.delta_integr_.size() == delta_size_ && "Wrong delta size");
+    assert(_motion_ref.delta_integr_cov_.cols() == delta_cov_size_ && "Wrong delta cov size");
+    assert(_motion_ref.delta_integr_cov_.rows() == delta_cov_size_ && "Wrong delta cov size");
+
+    assert(_motion_second.delta_.size() == delta_size_ && "Wrong delta size");
+    assert(_motion_second.delta_cov_.cols() == delta_cov_size_ && "Wrong delta cov size");
+    assert(_motion_second.delta_cov_.rows() == delta_cov_size_ && "Wrong delta cov size");
+    assert(_motion_second.delta_integr_.size() == delta_size_ && "Wrong delta size");
+    assert(_motion_second.delta_integr_cov_.cols() == delta_cov_size_ && "Wrong delta cov size");
+    assert(_motion_second.delta_integr_cov_.rows() == delta_cov_size_ && "Wrong delta cov size");
+
+    // reference
+    TimeStamp t_ref = _motion_ref.ts_;
+
+    // second
+    TimeStamp t_sec = _motion_second.ts_;
+    Map<VectorXs>    motion_sec_dp  (_motion_second.delta_.data() + 0, 3);
+    Map<Quaternions> motion_sec_dq  (_motion_second.delta_.data() + 3   );
+    Map<VectorXs>    motion_sec_dv  (_motion_second.delta_.data() + 7, 3);
+
+    // interpolated
+    Motion motion_int = motionZero(_ts);
+
+    // Jacobians for covariance propagation
+    MatrixXs J_ref(delta_cov_size_, delta_cov_size_);
+    MatrixXs J_int(delta_cov_size_, delta_cov_size_);
+
+    // interpolation factor
+    Scalar dt1    = _ts - t_ref;
+    Scalar dt2    = t_sec - _ts;
+    Scalar tau    = dt1 / (t_sec - t_ref); // interpolation factor (0 to 1)
+    Scalar tau_sq = tau * tau;
+
+    // copy data
+    motion_int.data_      = _motion_second.data_;
+    motion_int.data_cov_  = _motion_second.data_cov_;
+
+    // interpolate delta
+    motion_int.ts_        = _ts;
+    Map<VectorXs>    motion_int_dp  (motion_int.delta_.data() + 0, 3);
+    Map<Quaternions> motion_int_dq  (motion_int.delta_.data() + 3   );
+    Map<VectorXs>    motion_int_dv  (motion_int.delta_.data() + 7, 3);
+    motion_int_dp         = tau_sq * motion_sec_dp; // FIXME: delta_p not correctly interpolated
+    motion_int_dv         = tau    * motion_sec_dv;
+    motion_int_dq         = Quaternions::Identity().slerp(tau, motion_sec_dq);
+    motion_int.delta_cov_ = tau    * _motion_second.delta_cov_;
+
+    // integrate
+    deltaPlusDelta(_motion_ref.delta_integr_, motion_int.delta_, dt1, motion_int.delta_integr_, J_ref, J_int);
+    motion_int.delta_integr_cov_ = J_ref * _motion_ref.delta_integr_cov_ * J_ref.transpose()
+                                 + J_int * _motion_second.delta_cov_     * J_int.transpose();
+
+    // update second delta ( in place update )
+    motion_sec_dp = motion_int_dq.conjugate() * (motion_sec_dp - motion_int_dp - motion_int_dv * dt2);
+    motion_sec_dv = motion_int_dq.conjugate() * (motion_sec_dv - motion_int_dv);
+    motion_sec_dq = motion_int_dq.conjugate() *  motion_sec_dq;
+    _motion_second.delta_cov_ *= (1 - tau); // easy interpolation // TODO check for correctness
+    //Dp            = Dp; // trivial, just leave the code commented
+    //Dq            = Dq; // trivial, just leave the code commented
+    //_motion.delta_integr_cov_ = _motion.delta_integr_cov_; // trivial, just leave the code commented
+
+    return motion_int;
+}
+
 } // namespace wolf
 
 
diff --git a/src/processor_imu.h b/src/processor_imu.h
index ce1be08391d4ebcb6e2b7a35d97656b4b299e4c6..90ed5acc82df1a6130b45749cd934d63eb61c31c 100644
--- a/src/processor_imu.h
+++ b/src/processor_imu.h
@@ -4,24 +4,57 @@
 // Wolf
 #include "processor_motion.h"
 #include "frame_imu.h"
+#include "capture_imu.h"
+#include "feature_imu.h"
 
 
 namespace wolf {
-    
+WOLF_STRUCT_PTR_TYPEDEFS(ProcessorIMUParams);
+
+struct ProcessorIMUParams : public ProcessorParamsBase
+{
+        Scalar max_time_span;
+        Size   max_buff_length;
+        Scalar dist_traveled;
+        Scalar angle_turned;
+        bool voting_active; //IMU will not vote for key Frames to be created
+
+
+        ProcessorIMUParams() :
+            max_time_span(0.5),
+            max_buff_length(10),
+            dist_traveled(5),
+            angle_turned(.5),
+            voting_active(false)
+        {
+            type = "IMU";
+            name = "";
+        }
+};
+
 WOLF_PTR_TYPEDEFS(ProcessorIMU);
     
 //class
 class ProcessorIMU : public ProcessorMotion{
     public:
-        ProcessorIMU();
+        ProcessorIMU(ProcessorIMUParamsPtr _params = nullptr);
         virtual ~ProcessorIMU();
 
         //void getJacobians(Eigen::Matrix3s& _dDp_dab, Eigen::Matrix3s& _dDv_dab, Eigen::Matrix3s& _dDp_dwb, Eigen::Matrix3s& _dDv_dwb, Eigen::Matrix3s& _dDq_dwb);
 
     protected:
+        virtual void getCalibration(VectorXs& _bias)
+        {
+            FrameIMUPtr frame_imu = std::static_pointer_cast<FrameIMU>(getOriginPtr()->getFramePtr());
+            _bias << frame_imu->getAccBiasPtr()->getState() , frame_imu->getGyroBiasPtr()->getState();
+        }
         virtual void data2delta(const Eigen::VectorXs& _data,
                                 const Eigen::MatrixXs& _data_cov,
-                                const Scalar _dt);
+                                const Scalar _dt,
+                                Eigen::VectorXs& _delta,
+                                Eigen::MatrixXs& _delta_cov,
+                                const Eigen::VectorXs& _calib,
+                                Eigen::MatrixXs& _jacobian_calib);
         virtual void deltaPlusDelta(const Eigen::VectorXs& _delta_preint,
                                     const Eigen::VectorXs& _delta,
                                     const Scalar _dt,
@@ -32,20 +65,31 @@ class ProcessorIMU : public ProcessorMotion{
                                     Eigen::VectorXs& _delta_preint_plus_delta,
                                     Eigen::MatrixXs& _jacobian_delta_preint,
                                     Eigen::MatrixXs& _jacobian_delta);
-        virtual void xPlusDelta(const Eigen::VectorXs& _x,
+        virtual void statePlusDelta(const Eigen::VectorXs& _x,
                                 const Eigen::VectorXs& _delta,
                                 const Scalar _dt,
                                 Eigen::VectorXs& _x_plus_delta );
         virtual Eigen::VectorXs deltaZero() const;
+        virtual VectorXs correctDelta(const Motion& _motion, const CaptureMotionPtr _capture);
         virtual Motion interpolate(const Motion& _motion_ref,
                                    Motion& _motion,
                                    TimeStamp& _ts);
+        virtual bool voteForKeyFrame();
         virtual ConstraintBasePtr emplaceConstraint(FeatureBasePtr _feature_motion,
                                                    FrameBasePtr _frame_origin);
+        virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion, 
+                                                    FrameBasePtr _related_frame);
         void resetDerived();
 
     protected:
 
+        // keyframe voting parameters
+        Scalar max_time_span_;  // maximum time between keyframes
+        Size   max_buff_length_;// maximum buffer size before keyframe
+        Scalar dist_traveled_;  // maximum linear motion between keyframes
+        Scalar angle_turned_;   // maximum rotation between keyframes
+        bool voting_active_;    // IMU will be voting for KeyFrame only if this is true
+
         // Casted pointer to IMU frame
         FrameIMUPtr frame_imu_ptr_;
 
@@ -53,8 +97,8 @@ class ProcessorIMU : public ProcessorMotion{
         const Eigen::Vector3s gravity_;
 
         // Biases in the first keyframe's state for pre-integration
-        Eigen::Vector3s acc_bias_;
-        Eigen::Vector3s gyro_bias_;
+        Eigen::Map<Eigen::Vector3s> acc_bias_;
+        Eigen::Map<Eigen::Vector3s> gyro_bias_;
 
         // Maps to the received measurements
         Eigen::Map<Eigen::Vector3s> acc_measured_;
@@ -68,20 +112,18 @@ class ProcessorIMU : public ProcessorMotion{
         Eigen::Map<const Eigen::Quaternions> Dq_, dq_;
         Eigen::Map<Eigen::Quaternions> Dq_out_;
 
-        ///Jacobians of preintegrated delta wrt IMU biases
-        Eigen::Matrix3s dDp_dab_;
-        Eigen::Matrix3s dDv_dab_;
-        Eigen::Matrix3s dDp_dwb_;
-        Eigen::Matrix3s dDv_dwb_;
-        Eigen::Matrix3s dDq_dwb_;
-
         // Helper functions to remap several magnitudes
         virtual void remapPQV(const Eigen::VectorXs& _delta1, const Eigen::VectorXs& _delta2, Eigen::VectorXs& _delta_out);
         virtual void remapDelta(Eigen::VectorXs& _delta_out);
         virtual void remapData(const Eigen::VectorXs& _data);
 
-
     public:
+        //getters
+        Scalar getMaxTimeSpan() const;
+        Scalar getMaxBuffLength() const;
+        Scalar getDistTraveled() const;
+        Scalar getAngleTurned() const;
+        //for factory
         static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr = nullptr);
 };
 
@@ -101,14 +143,24 @@ namespace wolf{
 
 inline void ProcessorIMU::data2delta(const Eigen::VectorXs& _data,
                                      const Eigen::MatrixXs& _data_cov,
-                                     const Scalar _dt)
+                                     const Scalar _dt,
+                                     Eigen::VectorXs& _delta,
+                                     Eigen::MatrixXs& _delta_cov,
+                                     const Eigen::VectorXs& _calib,
+                                     Eigen::MatrixXs& _jacobian_calib)
 {
     assert(_data.size() == data_size_ && "Wrong data size!");
 
-    // remap
-    remapData(_data);
-    remapDelta(delta_);
-    // delta_ is D*_out_
+    using namespace Eigen;
+
+    // remap data
+    new (&acc_measured_) Map<const Vector3s>(_data.data());
+    new (&gyro_measured_) Map<const Vector3s>(_data.data() + 3);
+
+    // remap delta_ is D*_out_
+    new (&Dp_out_) Map<Vector3s>      (_delta.data() + 0);
+    new (&Dq_out_) Map<Quaternions>   (_delta.data() + 3);
+    new (&Dv_out_) Map<Vector3s>      (_delta.data() + 7);
 
     /* MATHS of delta creation -- Sola-16
      * dp = 1/2 * (a-a_b) * dt^2 = 1/2 * dv * dt
@@ -117,15 +169,16 @@ inline void ProcessorIMU::data2delta(const Eigen::VectorXs& _data,
      */
 
     // acc and gyro measurements corrected with the estimated bias
-    Eigen::Vector3s a = acc_measured_  - acc_bias_;
-    Eigen::Vector3s w = gyro_measured_ - gyro_bias_;
+    Vector3s a = acc_measured_  - _calib.head(3);
+    Vector3s w = gyro_measured_ - _calib.tail(3);
 
     // create delta
     Dv_out_ = a * _dt;
     Dp_out_ = Dv_out_ * _dt / 2;
     Dq_out_ = v2q(w * _dt);
 
-    //Compute jacobian of delta wrt data noise
+
+    //Compute jacobian of delta wrt data
 
     /* MATHS : jacobian dd_dn, of delta wrt noise
      * substituting a and w respectively by (a+a_n) and (w+w_n) (measurement noise is additive)
@@ -136,10 +189,10 @@ inline void ProcessorIMU::data2delta(const Eigen::VectorXs& _data,
      */
 
     // we go the sparse way:
-    Eigen::Matrix3s ddv_dan = Eigen::Matrix3s::Identity() * _dt;
-    Eigen::Matrix3s ddp_dan = ddv_dan * _dt / 2;
-    //    Eigen::Matrix3s ddo_dwn = jac_SO3_right(w * _dt) * _dt; // Since w*dt is small, we could use here  Jr(wdt) ~ (I - 0.5*[wdt]_x)  and go much faster.
-    Eigen::Matrix3s ddo_dwn = (Eigen::Matrix3s::Identity() - 0.5 * skew(w * _dt) ) * _dt; // voila, the comment above is this
+    Matrix3s ddv_dan = Matrix3s::Identity() * _dt;
+    Matrix3s ddp_dan = ddv_dan * _dt / 2;
+    Matrix3s ddo_dwn = jac_SO3_right(w * _dt) * _dt; // Since w*dt is small, we could use here  Jr(wdt) ~ (I - 0.5*[wdt]_x)  and go much faster.
+    //    Matrix3s ddo_dwn = (Matrix3s::Identity() - 0.5 * skew(w * _dt) ) * _dt; // voila, the comment above is this
 
     /* Covariance is sparse:
      *       [ Cpp   0   Cpv
@@ -148,11 +201,22 @@ inline void ProcessorIMU::data2delta(const Eigen::VectorXs& _data,
      *
      * where Cpp, Cpv, Coo and Cvv are computed below
      */
-    delta_cov_.block<3,3>(0,0).noalias() = ddp_dan*_data_cov.block<3,3>(0,0)*ddp_dan.transpose(); // Cpp = ddp_dan * Caa * ddp_dan'
-    delta_cov_.block<3,3>(0,6).noalias() = ddp_dan*_data_cov.block<3,3>(0,0)*ddv_dan.transpose(); // Cpv = ddp_dan * Caa * ddv_dan'
-    delta_cov_.block<3,3>(3,3).noalias() = ddo_dwn*_data_cov.block<3,3>(3,3)*ddo_dwn.transpose(); // Coo = ddo_dwn * Cww * ddo_dwn'
-    delta_cov_.block<3,3>(6,0)           = delta_cov_.block<3,3>(0,6).transpose();                // Cvp = Cpv'
-    delta_cov_.block<3,3>(6,6).noalias() = ddv_dan*_data_cov.block<3,3>(0,0)*ddv_dan.transpose(); // Cvv = ddv_dan * Caa * ddv_dan'
+    _delta_cov.block<3,3>(0,0).noalias() = ddp_dan*_data_cov.block<3,3>(0,0)*ddp_dan.transpose(); // Cpp = ddp_dan * Caa * ddp_dan'
+    _delta_cov.block<3,3>(0,6).noalias() = ddp_dan*_data_cov.block<3,3>(0,0)*ddv_dan.transpose(); // Cpv = ddp_dan * Caa * ddv_dan'
+    _delta_cov.block<3,3>(3,3).noalias() = ddo_dwn*_data_cov.block<3,3>(3,3)*ddo_dwn.transpose(); // Coo = ddo_dwn * Cww * ddo_dwn'
+    _delta_cov.block<3,3>(6,0)           = _delta_cov.block<3,3>(0,6).transpose();                // Cvp = Cpv'
+    _delta_cov.block<3,3>(6,6).noalias() = ddv_dan*_data_cov.block<3,3>(0,0)*ddv_dan.transpose(); // Cvv = ddv_dan * Caa * ddv_dan'
+
+
+    /* Jacobians of delta wrt calibration parameters -- bias
+     * We know that d_(meas - bias)/d_bias = -I
+     * so d_delta/d_bias = - d_delta/d_meas
+     * we assign only the non-null ones
+     */
+    _jacobian_calib.setZero(delta_cov_size_,calib_size_); // can be commented usually, more sure this way
+    _jacobian_calib.block(0,0,3,3) = - ddp_dan;
+    _jacobian_calib.block(3,3,3,3) = - ddo_dwn;
+    _jacobian_calib.block(6,0,3,3) = - ddv_dan;
 
 }
 
@@ -215,23 +279,25 @@ inline void ProcessorIMU::deltaPlusDelta(const Eigen::VectorXs& _delta_preint,
      */
 
     // Some useful temporaries
-    Eigen::Matrix3s DR = Dq_.matrix(); // First  Delta, DR
-    Eigen::Matrix3s dR = dq_.matrix(); // Second delta, dR
+    Matrix3s DR = Dq_.matrix(); // First  Delta, DR
+    Matrix3s dR = dq_.matrix(); // Second delta, dR
 
     // Jac wrt preintegrated delta, D_D = dD'/dD
-//    _jacobian_delta_preint.block<6,6>(0,0).setIdentity(6,6);                     // dDp'/dDp, dDv'/dDv, Identities
+    _jacobian_delta_preint.block<6,6>(0,0).setIdentity(6,6);                    // dDp'/dDp, dDv'/dDv, Identities
     _jacobian_delta_preint.block<3,3>(0,3).noalias() = - DR * skew(dp_) ;       // dDp'/dDo
-    _jacobian_delta_preint.block<3,3>(0,6) = Eigen::Matrix3s::Identity() * _dt; // dDp'/dDv = I*dt
+    _jacobian_delta_preint.block<3,3>(0,6) = Matrix3s::Identity() * _dt; // dDp'/dDv = I*dt
     _jacobian_delta_preint.block<3,3>(3,3) =   dR.transpose();                  // dDo'/dDo
     _jacobian_delta_preint.block<3,3>(6,3).noalias() = - DR * skew(dv_) ;       // dDv'/dDo
 
     // Jac wrt current delta, D_d = dD'/dd
-//    _jacobian_delta.setIdentity(9,9);                                           //
+    _jacobian_delta.setIdentity(9,9);                                           //
     _jacobian_delta.block<3,3>(0,0) = DR;                                       // dDp'/ddp
     _jacobian_delta.block<3,3>(6,6) = DR;                                       // dDv'/ddv
-//    _jacobian_delta.block<3,3>(3,3) = Eigen::Matrix3s::Identity();        // dDo'/ddo = I
+    _jacobian_delta.block<3,3>(3,3) = Matrix3s::Identity();        // dDo'/ddo = I
+
 
 
+    // DONE This needs to go out of here, Jac_calib is already taken care of by ProcessorMotion
 
      /*////////////////////////////////////////////////////////
       * 2. Integrate the Jacobians wrt the biases --
@@ -246,19 +312,25 @@ inline void ProcessorIMU::deltaPlusDelta(const Eigen::VectorXs& _delta_preint,
       */
 
     // acc and gyro measurements corrected with the estimated bias
-    Eigen::Vector3s a = acc_measured_  - acc_bias_;
-    Eigen::Vector3s w = gyro_measured_ - gyro_bias_;
-
-    // temporaries
-    Scalar dt2_2            = 0.5 * _dt * _dt;
-    Eigen::Matrix3s M_tmp   = DR * skew(a) * dDq_dwb_;
-
-    dDp_dab_.noalias()  += dDv_dab_ * _dt -  DR * dt2_2;
-    dDv_dab_            -= DR * _dt;
-    dDp_dwb_.noalias()  += dDv_dwb_ * _dt - M_tmp * dt2_2;
-    dDv_dwb_            -= M_tmp * _dt;
-    //    dDq_dwb_       = dR.transpose() * dDq_dwb_ - jac_SO3_right(w * _dt) * _dt; // See SOLA-16 -- we'll use small angle aprox below:
-    dDq_dwb_             = dR.transpose() * dDq_dwb_ - ( Eigen::Matrix3s::Identity() - 0.5*skew(w*_dt) )*_dt; // Small angle aprox of right Jacobian above
+//    Vector3s a = acc_measured_  - acc_bias_;
+//    Vector3s w = gyro_measured_ - gyro_bias_;
+//
+//    // temporaries
+//    Scalar dt2_2         = 0.5 * _dt * _dt;
+//    Matrix3s M_tmp       = DR * skew(a) * dDq_dwb_;
+//
+//    dDp_dab_.noalias()  += dDv_dab_ * _dt -    DR * dt2_2;
+//    dDv_dab_            -=       DR * _dt;
+//    dDp_dwb_.noalias()  += dDv_dwb_ * _dt - M_tmp * dt2_2;
+//    dDv_dwb_            -=    M_tmp * _dt;
+//    dDq_dwb_             = dR.transpose() * dDq_dwb_ - jac_SO3_right(w * _dt) * _dt; // See SOLA-16 -- we'll use small angle aprox below:
+//    //    dDq_dwb_             = dR.transpose() * dDq_dwb_ - ( Matrix3s::Identity() - 0.5*skew(w*_dt) )*_dt; // Small angle aprox of right Jacobian above
+//
+//    jacobian_calib_.block(0,0,3,3) = dDp_dab_;
+//    jacobian_calib_.block(0,3,3,3) = dDp_dwb_;
+//    jacobian_calib_.block(3,3,3,3) = dDq_dwb_;
+//    jacobian_calib_.block(6,0,3,3) = dDv_dab_;
+//    jacobian_calib_.block(6,3,3,3) = dDv_dwb_;
 
 
     /*//////////////////////////////////////////////////////////////////////////
@@ -303,7 +375,7 @@ inline void ProcessorIMU::deltaPlusDelta(const Eigen::VectorXs& _delta_preint,
     Dq_out_ = Dq_ * dq_;
 }
 
-inline void ProcessorIMU::xPlusDelta(const Eigen::VectorXs& _x,
+inline void ProcessorIMU::statePlusDelta(const Eigen::VectorXs& _x,
                                      const Eigen::VectorXs& _delta,
                                      const Scalar _dt,
                                      Eigen::VectorXs& _x_plus_delta)
@@ -314,7 +386,7 @@ inline void ProcessorIMU::xPlusDelta(const Eigen::VectorXs& _x,
     assert(_dt >= 0 && "Time interval _Dt is negative!");
 
 
-    Eigen::Vector3s gdt = gravity_ * _dt;
+    Vector3s gdt = gravity_ * _dt;
 
     // state updates
     remapPQV(_x, _delta, _x_plus_delta);
@@ -334,18 +406,6 @@ inline Eigen::VectorXs ProcessorIMU::deltaZero() const
     return (Eigen::VectorXs(10) << 0,0,0,  0,0,0,1,  0,0,0 ).finished(); // p, q, v
 }
 
-inline Motion ProcessorIMU::interpolate(const Motion& _motion_ref,
-                                        Motion& _motion,
-                                        TimeStamp& _ts)
-{
-    Motion tmp(_motion_ref);
-    tmp.ts_ = _ts;
-    tmp.delta_ = deltaZero();
-    tmp.delta_cov_ = Eigen::MatrixXs::Zero(delta_size_, delta_size_);
-    return tmp;
-}
-
-
 inline void ProcessorIMU::resetDerived()
 {
     // Cast a pointer to origin IMU frame
@@ -354,20 +414,13 @@ inline void ProcessorIMU::resetDerived()
     // Assign biases for the integration at the origin frame's biases
     acc_bias_  = frame_imu_ptr_->getAccBiasPtr()->getState(); // acc  bias
     gyro_bias_ = frame_imu_ptr_->getGyroBiasPtr()->getState(); // gyro bias
-
-    // reset jacobians wrt bias
-    dDp_dab_.setZero();
-    dDv_dab_.setZero();
-    dDp_dwb_.setZero();
-    dDv_dwb_.setZero();
-    dDq_dwb_.setZero();
 }
 
 inline ConstraintBasePtr ProcessorIMU::emplaceConstraint(FeatureBasePtr _feature_motion, FrameBasePtr _frame_origin)
 {
     FeatureIMUPtr ftr_imu = std::static_pointer_cast<FeatureIMU>(_feature_motion);
     FrameIMUPtr frm_imu = std::static_pointer_cast<FrameIMU>(_frame_origin);
-    ConstraintIMUPtr ctr_imu = std::make_shared<ConstraintIMU>(ftr_imu, frm_imu);
+    ConstraintIMUPtr ctr_imu = std::make_shared<ConstraintIMU>(ftr_imu, frm_imu, shared_from_this());
 
     _feature_motion->addConstraint(ctr_imu);
     _frame_origin->addConstrainedBy(ctr_imu);
@@ -375,44 +428,72 @@ inline ConstraintBasePtr ProcessorIMU::emplaceConstraint(FeatureBasePtr _feature
     return ctr_imu;
 }
 
+inline FeatureBasePtr ProcessorIMU::emplaceFeature(CaptureMotionPtr _capture_motion, FrameBasePtr _related_frame)
+{
+    // CaptureIMUPtr capt_imu = std::static_pointer_cast<CaptureIMU>(_capture_motion);
+    FrameIMUPtr key_frame_ptr = std::static_pointer_cast<FrameIMU>(_related_frame);
+    // create motion feature and add it to the key_capture
+//    MatrixXs delta_integr_cov(integrateBufferCovariance(_capture_motion->getBuffer()));
+    FeatureIMUPtr key_feature_ptr = std::make_shared<FeatureIMU>(
+            _capture_motion->getBuffer().get().back().delta_integr_,
+            _capture_motion->getBuffer().get().back().delta_integr_cov_,
+            key_frame_ptr->getAccBiasPtr()->getState(),
+            key_frame_ptr->getGyroBiasPtr()->getState(),
+            _capture_motion->getBuffer().get().back().jacobian_calib_);
+    _capture_motion->addFeature(key_feature_ptr);
+
+    return key_feature_ptr;
+}
+
 inline void ProcessorIMU::remapPQV(const Eigen::VectorXs& _delta1,
                                    const Eigen::VectorXs& _delta2,
                                    Eigen::VectorXs& _delta_out)
 {
-    new (&Dp_) Eigen::Map<const Eigen::Vector3s>    (_delta1.data() + 0);
-    new (&Dq_) Eigen::Map<const Eigen::Quaternions> (_delta1.data() + 3);
-    new (&Dv_) Eigen::Map<const Eigen::Vector3s>    (_delta1.data() + 7);
+    new (&Dp_) Map<const Vector3s>    (_delta1.data() + 0);
+    new (&Dq_) Map<const Quaternions> (_delta1.data() + 3);
+    new (&Dv_) Map<const Vector3s>    (_delta1.data() + 7);
 
-    new (&dp_) Eigen::Map<const Eigen::Vector3s>    (_delta2.data() + 0);
-    new (&dq_) Eigen::Map<const Eigen::Quaternions> (_delta2.data() + 3);
-    new (&dv_) Eigen::Map<const Eigen::Vector3s>    (_delta2.data() + 7);
+    new (&dp_) Map<const Vector3s>    (_delta2.data() + 0);
+    new (&dq_) Map<const Quaternions> (_delta2.data() + 3);
+    new (&dv_) Map<const Vector3s>    (_delta2.data() + 7);
 
-    new (&Dp_out_) Eigen::Map<Eigen::Vector3s>      (_delta_out.data() + 0);
-    new (&Dq_out_) Eigen::Map<Eigen::Quaternions>   (_delta_out.data() + 3);
-    new (&Dv_out_) Eigen::Map<Eigen::Vector3s>      (_delta_out.data() + 7);
+    new (&Dp_out_) Map<Vector3s>      (_delta_out.data() + 0);
+    new (&Dq_out_) Map<Quaternions>   (_delta_out.data() + 3);
+    new (&Dv_out_) Map<Vector3s>      (_delta_out.data() + 7);
 }
 
 inline void ProcessorIMU::remapDelta(Eigen::VectorXs& _delta_out)
 {
-    new (&Dp_out_) Eigen::Map<Eigen::Vector3s>      (_delta_out.data() + 0);
-    new (&Dq_out_) Eigen::Map<Eigen::Quaternions>   (_delta_out.data() + 3);
-    new (&Dv_out_) Eigen::Map<Eigen::Vector3s>      (_delta_out.data() + 7);
+    new (&Dp_out_) Map<Vector3s>      (_delta_out.data() + 0);
+    new (&Dq_out_) Map<Quaternions>   (_delta_out.data() + 3);
+    new (&Dv_out_) Map<Vector3s>      (_delta_out.data() + 7);
 }
 
 inline void ProcessorIMU::remapData(const Eigen::VectorXs& _data)
 {
-    new (&acc_measured_) Eigen::Map<const Eigen::Vector3s>(_data.data());
-    new (&gyro_measured_) Eigen::Map<const Eigen::Vector3s>(_data.data() + 3);
+    new (&acc_measured_) Map<const Vector3s>(_data.data());
+    new (&gyro_measured_) Map<const Vector3s>(_data.data() + 3);
+}
+
+inline Scalar ProcessorIMU::getMaxTimeSpan() const
+{
+    return max_time_span_;
+}
+
+inline Scalar ProcessorIMU::getMaxBuffLength() const
+{
+    return max_buff_length_;
 }
 
-/*void ProcessorIMU::getJacobians(Eigen::Matrix3s& _dDp_dab, Eigen::Matrix3s& _dDv_dab, Eigen::Matrix3s& _dDp_dwb, Eigen::Matrix3s& _dDv_dwb, Eigen::Matrix3s& _dDq_dwb)
+inline Scalar ProcessorIMU::getDistTraveled() const
 {
-    _dDp_dab = dDp_dab_;
-    _dDv_dab = dDv_dab_;
-    _dDp_dwb = dDp_dwb_;
-    _dDv_dwb = dDv_dwb_;
-    _dDq_dwb = dDq_dwb_;
-}*/
+    return dist_traveled_;
+}
+
+inline Scalar ProcessorIMU::getAngleTurned() const
+{
+    return angle_turned_;
+}
 
 } // namespace wolf
 
diff --git a/src/processor_imu_UnitTester.h b/src/processor_imu_UnitTester.h
index 8e8acd01094a429e28e25551b53dc48ed0a627d4..35209f3c8ad1694d539716a109d4bbb55f212d31 100644
--- a/src/processor_imu_UnitTester.h
+++ b/src/processor_imu_UnitTester.h
@@ -13,6 +13,31 @@ namespace wolf {
         IMU_jac_bias(Eigen::Matrix<Eigen::VectorXs,6,1> _Deltas_noisy_vect, Eigen::VectorXs _Delta0 , Eigen::Matrix3s _dDp_dab, Eigen::Matrix3s _dDv_dab, 
                     Eigen::Matrix3s _dDp_dwb, Eigen::Matrix3s _dDv_dwb, Eigen::Matrix3s _dDq_dwb) : Deltas_noisy_vect_(_Deltas_noisy_vect), Delta0_(_Delta0) ,
                     dDp_dab_(_dDp_dab), dDv_dab_(_dDv_dab), dDp_dwb_(_dDp_dwb), dDv_dwb_(_dDv_dwb), dDq_dwb_(_dDq_dwb){}
+                
+        IMU_jac_bias(){
+
+            for (int i=0; i<6; i++){
+                Deltas_noisy_vect_(i) = Eigen::VectorXs::Zero(1,1);
+            }
+
+            Delta0_ = Eigen::VectorXs::Zero(1,1);
+            dDp_dab_ = Eigen::Matrix3s::Zero();
+            dDv_dab_ = Eigen::Matrix3s::Zero();
+            dDp_dwb_ = Eigen::Matrix3s::Zero();
+            dDv_dwb_ = Eigen::Matrix3s::Zero();
+            dDq_dwb_ = Eigen::Matrix3s::Zero();
+        }
+
+        IMU_jac_bias(IMU_jac_bias const & toCopy){
+
+            Deltas_noisy_vect_ = toCopy.Deltas_noisy_vect_;
+            Delta0_ = toCopy.Delta0_;
+            dDp_dab_ = toCopy.dDp_dab_;
+            dDv_dab_ = toCopy.dDv_dab_;
+            dDp_dwb_ = toCopy.dDp_dwb_;
+            dDv_dwb_ = toCopy.dDv_dwb_;
+            dDq_dwb_ = toCopy.dDq_dwb_;
+        }
 
         public:
             /*The following vectors will contain all the matrices and deltas needed to compute the finite differences.
@@ -26,6 +51,19 @@ namespace wolf {
             Eigen::Matrix3s dDp_dwb_;
             Eigen::Matrix3s dDv_dwb_;
             Eigen::Matrix3s dDq_dwb_;
+
+
+        public:
+            void copyfrom(IMU_jac_bias const& right){
+
+                Deltas_noisy_vect_ = right.Deltas_noisy_vect_;
+                Delta0_ = right.Delta0_;
+                dDp_dab_ = right.dDp_dab_;
+                dDv_dab_ = right.dDv_dab_;
+                dDp_dwb_ = right.dDp_dwb_;
+                dDv_dwb_ = right.dDv_dwb_;
+                dDq_dwb_ = right.dDq_dwb_;
+            }
     };
 
     struct IMU_jac_deltas{
@@ -34,6 +72,29 @@ namespace wolf {
                         Eigen::MatrixXs _jacobian_delta_preint, Eigen::MatrixXs _jacobian_delta ) :
                         Delta0_(_Delta0), delta0_(_delta0), Delta_noisy_vect_(_Delta_noisy_vect), delta_noisy_vect_(_delta_noisy_vect), 
                        jacobian_delta_preint_(_jacobian_delta_preint), jacobian_delta_(_jacobian_delta) {}
+
+        IMU_jac_deltas(){
+            for (int i=0; i<9; i++){
+                Delta_noisy_vect_(i) = Eigen::VectorXs::Zero(1,1);
+                delta_noisy_vect_(i) = Eigen::VectorXs::Zero(1,1);
+            }
+
+            Delta0_ = Eigen::VectorXs::Zero(1,1);
+            delta0_ = Eigen::VectorXs::Zero(1,1);
+            jacobian_delta_preint_ = Eigen::MatrixXs::Zero(9,9);
+            jacobian_delta_ = Eigen::MatrixXs::Zero(9,9);
+        }
+
+        IMU_jac_deltas(IMU_jac_deltas const & toCopy){
+
+            Delta_noisy_vect_ = toCopy.Delta_noisy_vect_;
+            delta_noisy_vect_ = toCopy.delta_noisy_vect_;
+
+            Delta0_ = toCopy.Delta0_;
+            delta0_ = toCopy.delta0_;
+            jacobian_delta_preint_ = toCopy.jacobian_delta_preint_;
+            jacobian_delta_ = toCopy.jacobian_delta_;
+        }
         
         public:
             /*The following vectors will contain all the matrices and deltas needed to compute the finite differences.
@@ -41,8 +102,8 @@ namespace wolf {
                             Delta_noisy_vect_                                                                       delta_noisy_vect_
                             0: + 0,                                                                                 0: + 0
                             1: +dPx, 2: +dPy, 3: +dPz                                                               1: + dpx, 2: +dpy, 3: +dpz
-                            4: +dVx, 5: +dVy, 6: +dVz                                                               4: + dvx, 5: +dvy, 6: +dvz
-                            7: +dOx, 8: +dOy, 9: +dOz                                                               7: + dox, 8: +doy, 9: +doz
+                            4: +dOx, 5: +dOy, 6: +dOz                                                               4: + dox, 5: +doy, 6: +doz
+                            7: +dVx, 8: +dVy, 9: +dVz                                                               7: + dvx, 9: +dvy, +: +dvz
              */
             Eigen::VectorXs Delta0_; //this will contain the Delta not affected by noise
             Eigen::VectorXs delta0_; //this will contain the delta not affected by noise
@@ -50,6 +111,17 @@ namespace wolf {
             Eigen::Matrix<Eigen::VectorXs,9,1> delta_noisy_vect_; //this will contain the deltas affected by noises
             Eigen::MatrixXs jacobian_delta_preint_;
             Eigen::MatrixXs jacobian_delta_;
+
+        public:
+            void copyfrom(IMU_jac_deltas const& right){
+
+                Delta_noisy_vect_ = right.Delta_noisy_vect_;
+                delta_noisy_vect_ = right.delta_noisy_vect_;
+                Delta0_ = right.Delta0_;
+                delta0_ = right.delta0_;
+                jacobian_delta_preint_ = right.jacobian_delta_preint_;
+                jacobian_delta_ = right.jacobian_delta_;
+            }
     };
 
     class ProcessorIMU_UnitTester : public ProcessorIMU{
@@ -116,7 +188,9 @@ inline IMU_jac_bias ProcessorIMU_UnitTester::finite_diff_ab(const Scalar _dt, Ei
     data_cov = Eigen::MatrixXs::Zero(6,6);
     jacobian_delta_preint = Eigen::MatrixXs::Zero(9,9);
     jacobian_delta = Eigen::MatrixXs::Zero(9,9);
-    delta_preint_plus_delta0 << 0,0,0, 0,0,0, 1,0,0,0;
+    delta_preint_plus_delta0 << 0,0,0, 0,0,0,1 ,0,0,0; //PQV
+
+    Vector6s bias = Vector6s::Zero();
 
     /*The following vectors will contain all the matrices and deltas needed to compute the finite differences.
         place 1 : added da_bx in data         place 2 : added da_by in data       place 3 : added da_bz in data
@@ -126,14 +200,15 @@ inline IMU_jac_bias ProcessorIMU_UnitTester::finite_diff_ab(const Scalar _dt, Ei
     Eigen::Matrix3s dDp_dab, dDv_dab, dDp_dwb, dDv_dwb, dDq_dwb;
 
     //Deltas without use of da_b
-    data2delta(_data, data_cov, _dt);
+    data2delta(_data, data_cov, _dt,delta_,delta_cov_,bias,jacobian_delta_calib_);
     deltaPlusDelta(_delta_preint0, delta_, _dt, delta_preint_plus_delta0, jacobian_delta_preint, jacobian_delta);
+    MatrixXs jacobian_bias = jacobian_delta * jacobian_delta_calib_;
     Delta0 = delta_preint_plus_delta0; //this is the first preintegrated delta, not affected by any added bias noise
-    dDp_dab = dDp_dab_;
-    dDv_dab = dDv_dab_;
-    dDp_dwb = dDp_dwb_;
-    dDv_dwb = dDv_dwb_;
-    dDq_dwb = dDq_dwb_;
+    dDp_dab = jacobian_bias.block(0,0,3,3);
+    dDp_dwb = jacobian_bias.block(0,3,3,3);
+    dDq_dwb = jacobian_bias.block(3,3,3,3);
+    dDv_dab = jacobian_bias.block(6,0,3,3);
+    dDv_dwb = jacobian_bias.block(6,3,3,3);
     
 
     // propagate bias noise
@@ -141,19 +216,14 @@ inline IMU_jac_bias ProcessorIMU_UnitTester::finite_diff_ab(const Scalar _dt, Ei
         //need to reset stuff here
         acc_bias_ = Eigen::Vector3s::Zero();
         gyro_bias_ = Eigen::Vector3s::Zero();
-        dDp_dab_.setZero();
-        dDv_dab_.setZero();
-        dDp_dwb_.setZero();
-        dDv_dwb_.setZero();
-        dDq_dwb_.setZero();
-        delta_preint_plus_delta0 << 0,0,0, 0,0,0, 1,0,0,0;
+        delta_preint_plus_delta0 << 0,0,0, 0,0,0,1 ,0,0,0;  //PQV
         data_cov = Eigen::MatrixXs::Zero(6,6);
 
         // add da_b
         _data = data0;
         _data(i) = _data(i) - da_b; //- because a = a_m − a_b + a_n, in out case, a = a_m − a_b - da_b + a_n
         //data2delta
-        data2delta(_data, data_cov, _dt);
+        data2delta(_data, data_cov, _dt,delta_,delta_cov_,bias, jacobian_delta_calib_);
         deltaPlusDelta(_delta_preint0, delta_, _dt, delta_preint_plus_delta0, jacobian_delta_preint, jacobian_delta);
         Deltas_noisy_vect(i) = delta_preint_plus_delta0; //preintegrated deltas affected by added bias noise
     }
@@ -171,7 +241,7 @@ inline IMU_jac_deltas ProcessorIMU_UnitTester::finite_diff_noise(const Scalar& _
     Eigen::VectorXs delta_preint_plus_delta;
     delta0.resize(10);
     delta_preint_plus_delta.resize(10);
-    delta_preint_plus_delta << 0,0,0 ,0,0,0, 1,0,0,0;
+    delta_preint_plus_delta << 0,0,0 ,0,0,0,1 ,0,0,0;
 
     Eigen::MatrixXs jacobian_delta_preint;  //will be used as input for deltaPlusDelta
     Eigen::MatrixXs jacobian_delta;         //will be used as input for deltaPlusDelta
@@ -193,23 +263,35 @@ inline IMU_jac_deltas ProcessorIMU_UnitTester::finite_diff_noise(const Scalar& _
     Eigen::Matrix<Eigen::VectorXs,9,1> Delta_noisy_vect; //this will contain the Deltas affected by noises
     Eigen::Matrix<Eigen::VectorXs,9,1> delta_noisy_vect; //this will contain the deltas affected by noises
 
-    data2delta(_data, data_cov, _dt); //Affects dp_out, dv_out and dq_out
+    Vector6s bias = Vector6s::Zero();
+
+    data2delta(_data, data_cov, _dt,delta_,delta_cov_,bias,jacobian_delta_calib_); //Affects dp_out, dv_out and dq_out
     delta0 = delta_;        //save the delta that is not affected by noise
     deltaPlusDelta(_Delta0, delta0, _dt, delta_preint_plus_delta, jacobian_delta_preint, jacobian_delta); 
     jacobian_delta_preint0 = jacobian_delta_preint;
     jacobian_delta0 = jacobian_delta;
 
     //We compute all the jacobians wrt deltas and noisy deltas
-    for(int i=0; i<6; i++) //for 6 first component we just add to add noise as vector component since it is in the R^3 space
-    {
-
+    for(int i=0; i<3; i++) //for 3 first and 3 last components we just add to add noise as vector component since it is in the R^3 space
+    {   
+        //PQV formulation
+            //Add perturbation in position
         delta_ = delta0;
         delta_(i) = delta_(i) + _delta_noise(i); //noise has been added
         delta_noisy_vect(i) = delta_;
+
+            //Add perturbation in velocity
+            /*
+            delta_ is size 10 (P Q V),  _delta_noise is size 9 (P O V)
+            */
+        delta_ = delta0;
+        delta_(i+7) = delta_(i+7) + _delta_noise(i+6); //noise has been added
+        delta_noisy_vect(i+6) = delta_;
     }
 
     for(int i=0; i<3; i++) //for noise dtheta, it is in SO3, need to work on quaternions
-    {
+    {   
+        //PQV formulation
         //fist we need to reset some stuff
         Eigen::Matrix3s dqr_tmp;
         Eigen::Vector3s dtheta = Eigen::Vector3s::Zero();
@@ -217,18 +299,28 @@ inline IMU_jac_deltas ProcessorIMU_UnitTester::finite_diff_noise(const Scalar& _
         delta_ = delta0;
         remapDelta(delta_); //not sure that we need this
         dqr_tmp = Dq_out_.matrix();
-        dtheta(i) +=  _delta_noise(i+6); //introduce perturbation
+        dtheta(i) +=  _delta_noise(i+3); //introduce perturbation
         dqr_tmp = dqr_tmp * v2R(dtheta); //Apply perturbation : R * exp(dtheta) --> using matrix
         Dq_out_ = v2q(R2v(dqr_tmp)); //orientation noise has been added --> get back to quaternion form
-        delta_noisy_vect(i+6) = delta_;
+        delta_noisy_vect(i+3) = delta_;
     }
 
     //We compute all the jacobians wrt Deltas and noisy Deltas
-    for(int i=0; i<6; i++) //for 6 first component we just add to add noise as vector component since it is in the R^3 space
+    for(int i=0; i<3; i++) //for 3 first and 3 last components we just add to add noise as vector component since it is in the R^3 space
     {
+        //PQV formulation
+            //Add perturbation in position
         Delta_ = _Delta0;
         Delta_(i) = Delta_(i) + _Delta_noise(i); //noise has been added
         Delta_noisy_vect(i) = Delta_;
+
+            //Add perturbation in velocity
+            /*
+            Delta_ is size 10 (P Q V),  _Delta_noise is size 9 (P O V)
+            */
+        Delta_ = _Delta0;
+        Delta_(i+7) = Delta_(i+7) + _Delta_noise(i+6); //noise has been added
+        Delta_noisy_vect(i+6) = Delta_;
     }
 
     for(int i=0; i<3; i++) //for noise dtheta, it is in SO3, need to work on quaternions
@@ -240,10 +332,10 @@ inline IMU_jac_deltas ProcessorIMU_UnitTester::finite_diff_noise(const Scalar& _
         Delta_ = _Delta0;
         remapDelta(Delta_); //this time we need it
         dQr_tmp = Dq_out_.matrix();
-        dtheta(i) += _Delta_noise(i+6); //introduce perturbation
+        dtheta(i) += _Delta_noise(i+3); //introduce perturbation
         dQr_tmp = dQr_tmp * v2R(dtheta); //Apply perturbation : R * exp(dtheta) --> using matrix
         Dq_out_ = v2q(R2v(dQr_tmp)); //orientation noise has been added --> get back to quaternion form
-        Delta_noisy_vect(i+6) = Delta_;
+        Delta_noisy_vect(i+3) = Delta_;
     }
     
     IMU_jac_deltas jac_deltas(_Delta0, delta0, Delta_noisy_vect, delta_noisy_vect, jacobian_delta_preint0, jacobian_delta0);
diff --git a/src/processor_motion.cpp b/src/processor_motion.cpp
index 2a55839c2c1ea59de691669294ef8272d8bada39..227f476e0ecbacb3d20c2f248c120766e0014aab 100644
--- a/src/processor_motion.cpp
+++ b/src/processor_motion.cpp
@@ -3,23 +3,26 @@ namespace wolf
 {
 
 ProcessorMotion::ProcessorMotion(const std::string& _type, Size _state_size, Size _delta_size,
-                                 Size _delta_cov_size, Size _data_size, const Scalar& _time_tolerance) :
+                                 Size _delta_cov_size, Size _data_size, Scalar _time_tolerance, Size _calib_size) :
         ProcessorBase(_type, _time_tolerance),
         x_size_(_state_size),
+        data_size_(_data_size),
         delta_size_(_delta_size),
         delta_cov_size_(_delta_cov_size),
-        data_size_(_data_size),
+        calib_size_(_calib_size),
         origin_ptr_(),
         last_ptr_(),
         incoming_ptr_(),
         dt_(0.0), x_(_state_size),
+        data_(_data_size),
         delta_(_delta_size),
         delta_cov_(_delta_cov_size, _delta_cov_size),
         delta_integrated_(_delta_size),
         delta_integrated_cov_(_delta_cov_size, _delta_cov_size),
-        data_(_data_size),
+        calib_(_calib_size),
         jacobian_delta_preint_(delta_cov_size_, delta_cov_size_),
-        jacobian_delta_(delta_cov_size_, delta_cov_size_)
+        jacobian_delta_(delta_cov_size_, delta_cov_size_),
+        jacobian_calib_(delta_size_, calib_size_)
 {
     status_ = IDLE;
     //
@@ -32,7 +35,11 @@ ProcessorMotion::~ProcessorMotion()
 
 void ProcessorMotion::process(CaptureBasePtr _incoming_ptr)
 {
-
+  if (_incoming_ptr == nullptr)
+  {
+    WOLF_ERROR("Process got a nullptr !");
+    return;
+  }
 
     if (status_ == IDLE)
     {
@@ -60,8 +67,10 @@ void ProcessorMotion::process(CaptureBasePtr _incoming_ptr)
 //        std::cout << "PM: RUNNING" << std::endl;
     }
 
+    incoming_ptr_ = getIncomingCaptureMotion(_incoming_ptr);
 
-    incoming_ptr_ = std::static_pointer_cast<CaptureMotion>(_incoming_ptr);
+    /// @todo Anything else to do ?
+    if (incoming_ptr_ == nullptr) return;
 
     preProcess();
 
@@ -82,19 +91,17 @@ void ProcessorMotion::process(CaptureBasePtr _incoming_ptr)
         key_frame_ptr->setKey();
 
         // create motion feature and add it to the key_capture
-        delta_integrated_cov_ = integrateBufferCovariance(last_ptr_->getBuffer());
-        FeatureBasePtr key_feature_ptr = std::make_shared<FeatureBase>("MOTION", last_ptr_->getBuffer().get().back().delta_integr_, delta_integrated_cov_);
-        last_ptr_->addFeature(key_feature_ptr);
+        FeatureBasePtr key_feature_ptr = emplaceFeature(last_ptr_, key_frame_ptr);
 
         // create motion constraint and link it to parent feature and other frame (which is origin's frame)
-        auto ctr_ptr = emplaceConstraint(key_feature_ptr, origin_ptr_->getFramePtr());
+        /*auto ctr_ptr =*/ emplaceConstraint(key_feature_ptr, origin_ptr_->getFramePtr());
 
         // new capture
         CaptureMotionPtr new_capture_ptr = std::make_shared<CaptureMotion>(key_frame_ptr->getTimeStamp(),
                                                     getSensorPtr(),
                                                     Eigen::VectorXs::Zero(data_size_),
                                                     Eigen::MatrixXs::Zero(data_size_, data_size_),
-                                                    delta_size_, delta_cov_size_,
+                                                    data_size_, delta_size_, delta_cov_size_, calib_size_,
                                                     key_frame_ptr);
         // reset the new buffer
         new_capture_ptr->getBuffer().get().push_back( motionZero(key_frame_ptr->getTimeStamp()) ) ;
@@ -106,6 +113,7 @@ void ProcessorMotion::process(CaptureBasePtr _incoming_ptr)
         // reset integrals
         delta_integrated_ = deltaZero();
         delta_integrated_cov_.setZero();
+        jacobian_calib_.setZero();
 
         // reset processor origin to the new keyframe's capture
         origin_ptr_ = last_ptr_;
@@ -116,7 +124,6 @@ void ProcessorMotion::process(CaptureBasePtr _incoming_ptr)
 
         // callback to other processors
         getProblem()->keyFrameCallback(key_frame_ptr, shared_from_this(), time_tolerance_);
-
     }
 
 
@@ -155,10 +162,12 @@ CaptureMotionPtr ProcessorMotion::findCaptureContainingTimeStamp(const TimeStamp
     return capture_ptr;
 }
 
-void ProcessorMotion::setOrigin(const Eigen::VectorXs& _x_origin, const TimeStamp& _ts_origin)
+FrameBasePtr ProcessorMotion::setOrigin(const Eigen::VectorXs& _x_origin, const TimeStamp& _ts_origin)
 {
     FrameBasePtr key_frame_ptr = getProblem()->emplaceFrame(KEY_FRAME, _x_origin, _ts_origin);
     setOrigin(key_frame_ptr);
+
+    return key_frame_ptr;
 }
 
 void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame)
@@ -173,7 +182,7 @@ void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame)
                                                   getSensorPtr(),
                                                   Eigen::VectorXs::Zero(data_size_),
                                                   Eigen::MatrixXs::Zero(data_size_, data_size_),
-                                                  delta_size_, delta_cov_size_,
+                                                  data_size_, delta_size_, delta_cov_size_, calib_size_,
                                                   nullptr);
     // Add origin capture to origin frame
     _origin_frame->addCapture(origin_ptr_);
@@ -183,7 +192,7 @@ void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame)
                                                 getSensorPtr(),
                                                 Eigen::VectorXs::Zero(data_size_),
                                                 Eigen::MatrixXs::Zero(data_size_, data_size_),
-                                                delta_size_, delta_cov_size_,
+                                                data_size_, delta_size_, delta_cov_size_, calib_size_,
                                                 _origin_frame);
     // Make non-key-frame at last Capture
     FrameBasePtr new_frame_ptr = getProblem()->emplaceFrame(NON_KEY_FRAME,
@@ -201,6 +210,7 @@ void ProcessorMotion::setOrigin(FrameBasePtr _origin_frame)
     delta_integrated_ = deltaZero();
     delta_cov_.setZero();
     delta_integrated_cov_.setZero();
+    jacobian_calib_.setZero();
 
     // clear and reset buffer
     getBuffer().get().clear();
@@ -233,7 +243,7 @@ bool ProcessorMotion::keyFrameCallback(FrameBasePtr _new_keyframe, const Scalar&
     CaptureMotionPtr new_capture = std::make_shared<CaptureMotion>(new_ts, getSensorPtr(),
                                                                          Eigen::VectorXs::Zero(data_size_),
                                                                          Eigen::MatrixXs::Zero(data_size_, data_size_),
-                                                                         delta_size_, delta_cov_size_,
+                                                                         data_size_, delta_size_, delta_cov_size_, calib_size_,
                                                                          new_keyframe_origin);
     // add motion capture to keyframe
     _new_keyframe->addCapture(new_capture);
@@ -253,24 +263,8 @@ bool ProcessorMotion::keyFrameCallback(FrameBasePtr _new_keyframe, const Scalar&
         new_capture->getBuffer().get().push_back(motion_interpolated);
     }
 
-    Eigen::MatrixXs new_covariance = integrateBufferCovariance(new_capture->getBuffer());
-
-    // check for very small covariances and fix
-    // FIXME: This situation means no motion. Therefore, two KFs have been created at the same TS: the motion KF, and the other KF. Making a factor with nearly no cov is OK, but an overkill for a situation that should not have appeared.
-    if (new_covariance.determinant() < Constants::EPS_SMALL)
-    {
-        WOLF_DEBUG("Bad motion covariance determinant: ", new_covariance.determinant());
-        new_covariance += MatrixXs::Identity(delta_cov_size_, delta_cov_size_)*1e-4;
-        WOLF_DEBUG("Fixed motion covariance determinant: ", new_covariance.determinant());
-    }
-
     // create motion feature and add it to the capture
-    FeatureBasePtr new_feature = std::make_shared<FeatureBase>(
-            "ODOM 2D",
-            new_capture->getBuffer().get().back().delta_integr_,
-            new_covariance);
-
-    new_capture->addFeature(new_feature);
+    FeatureBasePtr new_feature = emplaceFeature(new_capture, new_keyframe_origin);
 
     // create motion constraint and add it to the feature, and link it to the other frame (origin)
     emplaceConstraint(new_feature, new_keyframe_origin);
@@ -291,12 +285,11 @@ bool ProcessorMotion::keyFrameCallback(FrameBasePtr _new_keyframe, const Scalar&
     // modify existing feature and constraint (if they exist in the existing capture)
     if (!existing_capture->getFeatureList().empty())
     {
-        FeatureBasePtr existing_feature = existing_capture->getFeatureList().back(); // there is only one feature!
+        auto existing_feature = existing_capture->getFeatureList().back(); // there is only one feature!
 
         // Modify existing feature --------
-        existing_feature->setMeasurement(existing_capture->getBuffer().get().back().delta_integr_);
-        MatrixXs existing_covariance = integrateBufferCovariance(existing_capture->getBuffer());
-        existing_feature->setMeasurementCovariance(existing_covariance);
+        existing_feature->setMeasurement          (existing_capture->getBuffer().get().back().delta_integr_);
+        existing_feature->setMeasurementCovariance(existing_capture->getBuffer().get().back().delta_integr_cov_);
 
         // Modify existing constraint --------
         // Instead of modifying, we remove one ctr, and create a new one.
@@ -313,23 +306,42 @@ void ProcessorMotion::integrateOneStep()
     // Set dt
     updateDt();
 
+    // get vector of parameters to calibrate
+    getCalibration(calib_);
+
     // get data and convert it to delta, and obtain also the delta covariance
-    data2delta(incoming_ptr_->getData(), incoming_ptr_->getDataCovariance(), dt_);
+    data2delta(incoming_ptr_->getData(), incoming_ptr_->getDataCovariance(), dt_, delta_, delta_cov_, getCalibration(), jacobian_delta_calib_);
 
     // integrate the current delta to pre-integrated measurements, and get Jacobians
     deltaPlusDelta(getBuffer().get().back().delta_integr_, delta_, dt_, delta_integrated_, jacobian_delta_preint_, jacobian_delta_);
 
-    // push all into buffer
-    getBuffer().get().push_back(Motion( {incoming_ptr_->getTimeStamp(), delta_, delta_integrated_,
-                                         jacobian_delta_, jacobian_delta_preint_, delta_cov_}));
+    // integrate Jacobian wrt calib
+    if (calib_size_ > 0)
+        jacobian_calib_ = jacobian_delta_preint_ * getBuffer().get().back().jacobian_calib_ + jacobian_delta_ * jacobian_delta_calib_;
 
+    // Integrate covariance
+    delta_integrated_cov_ = jacobian_delta_preint_ * getBuffer().get().back().delta_integr_cov_ * jacobian_delta_preint_.transpose()
+                          + jacobian_delta_        * delta_cov_                                 * jacobian_delta_.transpose();
+
+    // push all into buffer
+    getBuffer().get().emplace_back(incoming_ptr_->getTimeStamp(),
+                                   incoming_ptr_->getData(),
+                                   incoming_ptr_->getDataCovariance(),
+                                   delta_,
+                                   delta_cov_,
+                                   delta_integrated_,
+                                   delta_integrated_cov_,
+                                   jacobian_delta_,
+                                   jacobian_delta_preint_,
+                                   jacobian_calib_);
 }
 
 void ProcessorMotion::reintegrateBuffer(CaptureMotionPtr _capture_ptr)
 {
-
     // start with empty motion
     _capture_ptr->getBuffer().get().push_front(motionZero(_capture_ptr->getOriginFramePtr()->getTimeStamp()));
+
+    // Iterate all the buffer
     auto motion_it = _capture_ptr->getBuffer().get().begin();
     auto prev_motion_it = motion_it;
     motion_it++;
@@ -338,20 +350,60 @@ void ProcessorMotion::reintegrateBuffer(CaptureMotionPtr _capture_ptr)
         // get dt
         const Scalar dt = motion_it->ts_ - prev_motion_it->ts_;
 
+        // re-convert data to delta with the new calibration parameters
+        // FIXME: Get calibration params from Capture or capture->Sensor
+        VectorXs calib = getCalibration();
+
+        data2delta(motion_it->data_, motion_it->data_cov_, dt, motion_it->delta_, motion_it->delta_cov_, calib, jacobian_delta_calib_);
+
         // integrate delta into delta_integr, and rewrite the buffer
         deltaPlusDelta(prev_motion_it->delta_integr_, motion_it->delta_, dt, motion_it->delta_integr_,
                        motion_it->jacobian_delta_integr_, motion_it->jacobian_delta_);
 
+        // integrate Jacobian wrt calib
+        if (calib_size_ > 0)
+            motion_it->jacobian_calib_ = motion_it->jacobian_delta_integr_ * prev_motion_it->jacobian_calib_ + motion_it->jacobian_delta_ * jacobian_delta_calib_;
+
+        // Integrate covariance
+        motion_it->delta_integr_cov_ = motion_it->jacobian_delta_integr_ * prev_motion_it->delta_integr_cov_ * motion_it->jacobian_delta_integr_.transpose()
+                                     + motion_it->jacobian_delta_        * motion_it->delta_cov_             * motion_it->jacobian_delta_.transpose();
+
         // advance in buffer
         motion_it++;
         prev_motion_it++;
     }
 }
 
-Eigen::MatrixXs ProcessorMotion::integrateBufferCovariance(const MotionBuffer& _motion_buffer)
+CaptureMotionPtr ProcessorMotion::getIncomingCaptureMotion(CaptureBasePtr& _incoming_ptr)
 {
-    return _motion_buffer.integrateCovariance();
+  return std::static_pointer_cast<CaptureMotion>(_incoming_ptr);
 }
 
+CaptureMotionPtr ProcessorMotion::getCaptureMotionContainingTimeStamp(const TimeStamp& _ts)
+{
+    // We need to search in previous keyframes for the capture containing a motion buffer with the queried time stamp
+    // Note: since the buffer goes from a FK through the past until the previous KF, we need to:
+    //  1. See that the KF contains a CaptureMotion
+    //  2. See that the TS is smaller than the KF's TS
+    //  3. See that the TS is bigger than the KF's first Motion in the CaptureMotion's buffer
+    FrameBasePtr frame = nullptr;
+    CaptureBasePtr capture = nullptr;
+    CaptureMotionPtr capture_motion = nullptr;
+    for (auto frame_iter = getProblem()->getTrajectoryPtr()->getFrameList().rbegin();
+            frame_iter != getProblem()->getTrajectoryPtr()->getFrameList().rend(); ++frame_iter)
+    {
+        frame = *frame_iter;
+        capture = frame->getCaptureOf(getSensorPtr());
+        if (capture != nullptr)
+        {
+            // We found a Capture belonging to this processor's Sensor ==> it is a CaptureMotion
+            capture_motion = std::static_pointer_cast<CaptureMotion>(capture);
+            if (_ts >= capture_motion->getBuffer().get().front().ts_)
+                // Found time stamp satisfying rule 3 above !!
+                break;
+        }
+    }
+    return capture_motion;
+}
 
 }
diff --git a/src/processor_motion.h b/src/processor_motion.h
index 77b1ab8e809c2ac8a6eb20312cfba9fdf2efe31b..cd1c41c7f9e2fbe784abfef79ba91768e2afba95 100644
--- a/src/processor_motion.h
+++ b/src/processor_motion.h
@@ -79,7 +79,7 @@ namespace wolf
  * Only when the motion delta is expressed in the robot frame R, we can integrate it
  * on top of the current Robot frame: R <-- R (+) delta_R
  *
- *     \code    xPlusDelta(R_old, delta_R, R_new) \endcode
+ *     \code    statePlusDelta(R_old, delta_R, R_new) \endcode
  *
  *
  * ### Defining (or not) the fromSensorFrame():
@@ -108,12 +108,18 @@ class ProcessorMotion : public ProcessorBase
 
     // This is the main public interface
     public:
-        ProcessorMotion(const std::string& _type, Size _state_size, Size _delta_size, Size _delta_cov_size, Size _data_size, const Scalar& _time_tolerance = 0.1);
+        ProcessorMotion(const std::string& _type,
+                        Size _state_size,
+                        Size _delta_size,
+                        Size _delta_cov_size,
+                        Size _data_size,
+                        Scalar _time_tolerance = 0.1,
+                        Size _calib_size = 0);
         virtual ~ProcessorMotion();
 
         // Instructions to the processor:
 
-        virtual void process(CaptureBasePtr _incoming_ptr);
+        void process(CaptureBasePtr _incoming_ptr);
         virtual void resetDerived();
 
         // Queries to the processor:
@@ -137,12 +143,6 @@ class ProcessorMotion : public ProcessorBase
          */
         void getCurrentStateAndStamp(Eigen::VectorXs& _x, TimeStamp& _ts);
 
-        /** \brief Get the state integrated so far and its stamp
-         * \param _ts the returned stamp
-         * return the state vector
-         */
-        Eigen::VectorXs getCurrentStateAndStamp(TimeStamp& _ts);
-
         /** \brief Fill the state corresponding to the provided time-stamp
          * \param _ts the time stamp
          * \param _x the returned state
@@ -155,10 +155,16 @@ class ProcessorMotion : public ProcessorBase
          */
         Eigen::VectorXs getState(const TimeStamp& _ts);
 
+        /** \brief Gets the delta preintegrated covariance from all integrations so far
+         * \return the delta preintegrated covariance matrix
+         */
+        const Eigen::MatrixXs getCurrentDeltaPreintCov();
+
         /** \brief Provide the motion integrated so far
          * \return the integrated delta state
          */
         Motion getMotion() const;
+
         void getMotion(Motion& _motion) const;
 
         /** \brief Provide the motion integrated until a given timestamp
@@ -172,15 +178,6 @@ class ProcessorMotion : public ProcessorBase
          */
         CaptureMotionPtr findCaptureContainingTimeStamp(const TimeStamp& _ts) const;
 
-        /** Composes the deltas in two pre-integrated Captures
-         * \param _cap1_ptr pointer to the first Capture
-         * \param _cap2_ptr pointer to the second Capture. This is local wrt. the first Capture.
-         * \param _delta1_plus_delta2 the concatenation of the deltas of Captures 1 and 2.
-         */
-        void sumDeltas(CaptureMotionPtr _cap1_ptr,
-                       CaptureMotionPtr _cap2_ptr,
-                       Eigen::VectorXs& _delta1_plus_delta2);
-
         /** Set the origin of all motion for this processor
          * \param _origin_frame the keyframe to be the origin
          */
@@ -190,23 +187,61 @@ class ProcessorMotion : public ProcessorBase
          * \param _x_origin the state at the origin
          * \param _ts_origin origin timestamp.
          */
-        void setOrigin(const Eigen::VectorXs& _x_origin, const TimeStamp& _ts_origin);
+        FrameBasePtr setOrigin(const Eigen::VectorXs& _x_origin, const TimeStamp& _ts_origin);
 
         virtual bool keyFrameCallback(FrameBasePtr _keyframe_ptr, const Scalar& _time_tol);
 
         MotionBuffer& getBuffer();
         const MotionBuffer& getBuffer() const;
 
-        Eigen::MatrixXs integrateBufferCovariance(const MotionBuffer& _motion_buffer);
+        /** \brief get calibration params
+         *
+         * @param _calib a reference to the calibration params vector
+         */
+        virtual void getCalibration (VectorXs& _calib)
+        {
+            assert(_calib.size() == calib_size_);
+
+            Size i = 0;
+            // Check Capture's intrinsics and extrinsics for the fix() flag
+            for (auto sb : getSensorPtr()->getStateBlockVec()) // FIXME: get from Capture, not from Sensor!!
+            {
+                if (sb && !( sb->isFixed() ) )
+                {
+                    _calib.segment(i, i+sb->getSize() ) = sb->getState();
+                    i += sb->getSize();
+                }
+            }
+        }
+
+        /** \brief get calibration parameters
+         *
+         * @return a vector with the calibration parameters
+         */
+        VectorXs getCalibration()
+        {
+            VectorXs calib(calib_size_);
+            getCalibration(calib);
+            return calib;
+        }
 
-        // Helper functions:
-    protected:
+        void getJacobianCalib(MatrixXs& _jac_cal)
+        {
+            _jac_cal = getBuffer().get().back().jacobian_calib_;
+        }
 
-        void splitBuffer(const TimeStamp& _t_split, MotionBuffer& _oldest_part);
+        MatrixXs getJacobianCalib()
+        {
+            return getBuffer().get().back().jacobian_calib_;
+        }
 
+
+        // Helper functions:
     protected:
+
         void updateDt();
         void integrateOneStep();
+        void splitBuffer(const TimeStamp& _t_split, MotionBuffer& _oldest_part);
         void reintegrateBuffer(CaptureMotionPtr _capture_ptr);
 
         /** Pre-process incoming Capture
@@ -234,24 +269,37 @@ class ProcessorMotion : public ProcessorBase
          */
         virtual void postProcess() { };
 
+        /**
+         * @brief Get the incoming CaptureBasePtr and returns a CaptureMotionPtr out of it.
+         * If not overloaded, the base class calls
+         * std::static_pointer_cast<CaptureMotion>(_incoming_ptr)
+         * @return CaptureMotionPtr.
+         */
+        virtual CaptureMotionPtr getIncomingCaptureMotion(CaptureBasePtr& _incoming_ptr);
+
 
         // These are the pure virtual functions doing the mathematics
     protected:
 
+
         /** \brief convert raw CaptureMotion data to the delta-state format
          *
          * This function accepts raw data and time step dt,
          * and computes the value of the delta-state and its covariance. Note that these values are
          * held by the members delta_ and delta_cov_.
          *
-         * \param _data the raw motion data
-         * \param _data_cov the raw motion data covariance
-         * \param _dt the time step (not always needed)
+         * @param _data measured motion data
+         * @param _data_cov covariance
+         * @param _dt time step
+         * @param _delta computed delta
+         * @param _delta_cov covariance
+         * @param _calib current state of the calibrated parameters
+         * @param _jacobian_calib Jacobian of the delta wrt calib
          *
          * Rationale:
          *
          * The delta-state format must be compatible for integration using
-         * the composition functions doing the math in this class: xPlusDelta() and deltaPlusDelta().
+         * the composition functions doing the math in this class: statePlusDelta() and deltaPlusDelta().
          * See the class documentation for some Eigen::VectorXs suggestions.
          *
          * The data format is generally not the same as the delta format,
@@ -288,7 +336,11 @@ class ProcessorMotion : public ProcessorBase
          */
         virtual void data2delta(const Eigen::VectorXs& _data,
                                 const Eigen::MatrixXs& _data_cov,
-                                const Scalar _dt) = 0;
+                                const Scalar _dt,
+                                Eigen::VectorXs& _delta,
+                                Eigen::MatrixXs& _delta_cov,
+                                const Eigen::VectorXs& _calib,
+                                Eigen::MatrixXs& _jacobian_calib) = 0;
 
         /** \brief composes a delta-state on top of another delta-state
          * \param _delta1 the first delta-state
@@ -328,11 +380,23 @@ class ProcessorMotion : public ProcessorBase
          *
          * This function implements the composition (+) so that _x2 = _x1 (+) _delta.
          */
-        virtual void xPlusDelta(const Eigen::VectorXs& _x,
+        virtual void statePlusDelta(const Eigen::VectorXs& _x,
                                 const Eigen::VectorXs& _delta,
                                 const Scalar _dt,
                                 Eigen::VectorXs& _x_plus_delta) = 0;
 
+        /** \brief Correct delta according to new initial values
+         *
+         * Since delta_integr_ may depend linearly on some parameters,
+         * at the time these params change, the delta must be corrected.
+         * This is implemented here with a trivial function,
+         * and can be overloaded in derived classes.
+         * @return the corrected delta.
+         */
+        virtual VectorXs correctDelta(const Motion & _motion, const CaptureMotionPtr _capture)
+        {
+            return _motion.delta_integr_;
+        }
 
         /** \brief Delta zero
          * \return a delta state equivalent to the null motion.
@@ -365,36 +429,36 @@ class ProcessorMotion : public ProcessorBase
          *
          * Let us name
          *
-         * ```
+         *
          *     R = _ref      // initial motion where interpolation starts
          *     F = _second   // final motion where interpolation ends
-         * ```
+         *
          * and let us define
          *
-         * ```
+         *
          *     t_R            // timestamp at R
          *     t_F            // timestamp at F
          *     t_I = _ts      // time stamp where interpolation is queried.
-         * ```
+         *
          * We can introduce the results of the interpolation as
          *
-         * ```
+         *
          *     I = motion_interpolated // from t_R to t_I
          *     S = motion_second       // from t_I to t_F
-         * ```
+         *
          * The Motion structure in wolf has the following members (among others; see below):
          *
-         * ```
+         *
          *     ts_           // time stamp
          *     delta_        // relative motion between the previous motion and this one. It might be seen as a local motion.
          *     delta_integr_ // integration of relative deltas, since some origin. It might be seen as a globally defined motion.
-         * ```
+         *
          * In this documentation, we differentiate these deltas with lower-case d and upper-case D:
          *
-         * ```
+         *
          *     d = any_motion.delta_            // local delta, from previous to this
          *     D = any_motion.delta_integr_     // global Delta, from origin to this
-         * ```
+         *
          * so that `D_(i+1) = D_(i) (+) d_(i+1)`, where (i) is in {R, I, S} and (i+1) is in {I, S, F}
          *
          * NOTE: the operator (+) is implemented as `deltaPlusDelta()` in each class deriving from this.
@@ -421,15 +485,15 @@ class ProcessorMotion : public ProcessorBase
          * where '`origin`' exists somewhere, but it is irrelevant for the operation of the interpolation.
          * According to the schematic, and assuming a generic composition operator (+), the motion composition satisfies
          *
-         * ```
+         *
          *   d_I (+) d_S = d_F      (1)
-         * ```
+         *
          * from where `d_I` and `d_S` are first derived. Then, the integrated deltas satisfy
          *
-         * ```
+         *
          *   D_I = D_R (+) d_I      (2)
          *   D_S = D_F              (3)
-         * ```
+         *
          * from where `D_I` and `D_S` can be derived.
          *
          * ### Interpolating `d_I`
@@ -443,16 +507,16 @@ class ProcessorMotion : public ProcessorBase
          * Therefore, we consider a linear interpolation.
          * The linear interpolation factor `tau` is defined from the time stamps,
          *
-         * ```
+         *
          *     tau = (t_I - t_R) / (t_F - t_R)
-         * ```
+         *
          * such that for `tau=0` we are at `R`, and for `tau=1` we are at `F`.
          *
          * Conceptually, we want an interpolation such that the local motion 'd' takes the fraction,
          *
-         * ```
+         *
          *   d_I = tau (*) d_F       // the fraction of the local delta
-         * ```
+         *
          * where again the operator (*) needs to be defined properly.
          *
          * ### Defining the operators (*), (+), and (-)
@@ -471,17 +535,17 @@ class ProcessorMotion : public ProcessorBase
          * #### Operator (*)
          *
          *   - for linear magnitudes, (*) is the regular product *:
-         * ```
+         *
          *         dv_I = tau * dv_F
-         * ```
+         *
          *   - for simple angles, (*) is the regular product:
-         * ```
+         *
          *         da_I = tau * da_F
-         * ```
+         *
          *   - for quaternions, we use slerp():
-         * ```
+         *
          *     dq_I = 1.slerp(tau, dq_F) // '1' is the unit quaternion
-         * ```
+         *
          *
          * #### Operator (+)
          *
@@ -520,35 +584,35 @@ class ProcessorMotion : public ProcessorBase
          * For simple pose increments, we can use a local implementation:
          *
          *   - for 2D
-         * ```
+         *
          *     dp_S = dR_I.tr * (1-tau)*dp_F      // dR is the rotation matrix of the angle delta 'da'; 'tr' is transposed
          *     da_S = dR_I.tr * (1-tau)*da_F
-         * ```
+         *
          *   - for 3D
-         * ```
+         *
          *     dp_S = dq_I.conj * (1-tau)*dp_F    // dq is a quaternion; 'conj' is the conjugate quaternion.
          *     dq_S = dq_I.conj * dq_F
-         * ```
+         *
          *
          * Please refer to the examples at the end of this documentation for the computation of `d_S`.
          *
          * ### Computing `D_I`
          *
          * Conceptually, the global motion 'D' is interpolated, that is:
-         * ```
+         *
          *     D_I = (1-tau) (*) D_R (+) tau (*) D_F  // the interpolation of the global Delta
-         * ```
+         *
          * However, we better make use of (2) and write
-         * ```
+         *
          *     D_I = D_R (+) d_I
          *         = deltaPlusDelta(D_R, d_I)         // This form provides an easy implementation.
-         * ```
+         *
          *
          * ### Examples
          *
          * #### Example 1: For 2D poses
          *
-         * ```
+         *
          *     t_I  = _ts                         // time stamp of the interpolated motion
          *     tau = (t_I - t_R) / (t_F - t_R)    // interpolation factor
          *
@@ -561,11 +625,11 @@ class ProcessorMotion : public ProcessorBase
          *     da_S = dR_I.tr * (1-tau)*da_F
          *
          *     D_S  = D_F
-         * ```
+         *
          * #### Example 2: For 3D poses
          *
          * Orientation is in quaternion form, which is the best for interpolation using `slerp()` :
-         * ```
+         *
          *     t_I  = _ts                         // time stamp of the interpolated motion
          *     tau = (t_I - t_R) / (t_F - t_R)    // interpolation factor
          *
@@ -578,7 +642,7 @@ class ProcessorMotion : public ProcessorBase
          *     dq_S = dq_I.conj * dq_F
          *
          *     D_S  = D_F
-         * ```
+         *
          */
         /* //TODO: JS: Remove these instructions since we will remove covariances from Motion.
          *
@@ -590,15 +654,15 @@ class ProcessorMotion : public ProcessorBase
          *     DC: delta_integr_cov_
          *
          * and which are integrated as follows
-         * ```
+         *
          *     dC_I = tau * dC_F
          *     DC_I = (1-tau) * DC_R + tau * dC_F = DC_R + dC_I
-         * ```
+         *
          * and
-         * ```
+         *
          *     dC_S = (1-tau) * dC_F
          *     DC_S = DC_F
-         * ```
+         *
          */
         virtual Motion interpolate(const Motion& _ref, Motion& _second, TimeStamp& _ts) = 0;
 
@@ -608,7 +672,14 @@ class ProcessorMotion : public ProcessorBase
          */
         virtual ConstraintBasePtr emplaceConstraint(FeatureBasePtr _feature_motion, FrameBasePtr _frame_origin) = 0;
 
+        /** \brief create a feature corresponding to given capture and add the feature to this capture
+         * \param _capture_motion: the parent capture
+         * \param _related_frame: frame of the last_ptr set as KEYFRAME. (used only in processor_imu.h for now...)
+         */
+        virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion, FrameBasePtr _related_frame) = 0;
+
         Motion motionZero(const TimeStamp& _ts);
+        CaptureMotionPtr getCaptureMotionContainingTimeStamp(const TimeStamp& _ts);
 
     public:
         virtual CaptureBasePtr getOriginPtr();
@@ -619,24 +690,28 @@ class ProcessorMotion : public ProcessorBase
     protected:
         // Attributes
         Size x_size_;           ///< The size of the state vector
+        Size data_size_;        ///< the size of the incoming data
         Size delta_size_;       ///< the size of the deltas
         Size delta_cov_size_;   ///< the size of the delta covariances matrix
-        Size data_size_;        ///< the size of the incoming data
-        CaptureBasePtr origin_ptr_; // TODO check pointer type
-        CaptureMotionPtr last_ptr_; // TODO check pointer type
-        CaptureMotionPtr incoming_ptr_; // TODO check pointer type
+        Size calib_size_;       ///< size of the extra parameters (TBD in derived classes)
+        CaptureBasePtr origin_ptr_;
+        CaptureMotionPtr last_ptr_;
+        CaptureMotionPtr incoming_ptr_;
 
     protected:
         // helpers to avoid allocation
         Scalar dt_;                             ///< Time step
         Eigen::VectorXs x_;                     ///< current state
+        Eigen::VectorXs data_;                  ///< current data
         Eigen::VectorXs delta_;                 ///< current delta
         Eigen::MatrixXs delta_cov_;             ///< current delta covariance
         Eigen::VectorXs delta_integrated_;      ///< integrated delta
         Eigen::MatrixXs delta_integrated_cov_;  ///< integrated delta covariance
-        Eigen::VectorXs data_;                  ///< current data
+        Eigen::VectorXs calib_;                 ///< calibration vector
         Eigen::MatrixXs jacobian_delta_preint_; ///< jacobian of delta composition w.r.t previous delta integrated
         Eigen::MatrixXs jacobian_delta_;        ///< jacobian of delta composition w.r.t current delta
+        Eigen::MatrixXs jacobian_calib_;        ///< jacobian of delta preintegration wrt calibration params
+        Eigen::MatrixXs jacobian_delta_calib_;  ///< jacobian of delta wrt calib params
 
     private:
         wolf::TimeStamp getCurrentTimeStamp();
@@ -672,7 +747,34 @@ inline Eigen::VectorXs ProcessorMotion::getState(const TimeStamp& _ts)
 
 inline void ProcessorMotion::getState(const TimeStamp& _ts, Eigen::VectorXs& _x)
 {
-    xPlusDelta(origin_ptr_->getFramePtr()->getState(), getBuffer().getDelta(_ts), _ts - origin_ptr_->getTimeStamp(), _x);
+    if (_ts >= origin_ptr_->getTimeStamp())
+    {
+        // timestamp found in the current processor buffer
+        statePlusDelta(origin_ptr_->getFramePtr()->getState(), getBuffer().getDelta(_ts), _ts - origin_ptr_->getTimeStamp(), _x);
+    }
+    else
+    {
+        // We need to search in previous keyframes for the capture containing a motion buffer with the queried time stamp
+        CaptureMotionPtr capture_motion = getCaptureMotionContainingTimeStamp(_ts);
+
+        if (capture_motion)
+        {
+            // We found a CaptureMotion whose buffer contains the time stamp
+            VectorXs         state_0        = capture_motion->getOriginFramePtr()->getState();
+            Motion           motion         = capture_motion->getBuffer().getMotion(_ts);
+            VectorXs         delta          = capture_motion->getBuffer().getDelta(_ts);
+            Scalar           dt             = _ts - capture_motion->getBuffer().get().front().ts_;
+
+            VectorXs delta_corrected = correctDelta(motion, capture_motion);
+
+            statePlusDelta(state_0, delta_corrected, dt, _x);
+        }
+        else
+        {
+            // We could not find any CaptureMotion for the time stamp requested
+            std::runtime_error("Could not find any Capture for the time stamp requested");
+        }
+    }
 }
 
 inline wolf::TimeStamp ProcessorMotion::getCurrentTimeStamp()
@@ -686,16 +788,10 @@ inline Eigen::VectorXs ProcessorMotion::getCurrentState()
     return x_;
 }
 
-inline Eigen::VectorXs ProcessorMotion::getCurrentStateAndStamp(TimeStamp& _ts)
-{
-    getCurrentStateAndStamp(x_, _ts);
-    return x_;
-}
-
 inline void ProcessorMotion::getCurrentState(Eigen::VectorXs& _x)
 {
     Scalar Dt = getBuffer().get().back().ts_ - origin_ptr_->getTimeStamp();
-    xPlusDelta(origin_ptr_->getFramePtr()->getState(), getBuffer().get().back().delta_integr_, Dt, _x);
+    statePlusDelta(origin_ptr_->getFramePtr()->getState(), getBuffer().get().back().delta_integr_, Dt, _x);
 }
 
 inline void ProcessorMotion::getCurrentStateAndStamp(Eigen::VectorXs& _x, TimeStamp& _ts)
@@ -704,6 +800,12 @@ inline void ProcessorMotion::getCurrentStateAndStamp(Eigen::VectorXs& _x, TimeSt
     _ts = getCurrentTimeStamp();
 }
 
+inline const Eigen::MatrixXs ProcessorMotion::getCurrentDeltaPreintCov()
+{
+    return getBuffer().get().back().delta_integr_cov_;
+//    return delta_integrated_cov_;
+}
+
 inline Motion ProcessorMotion::getMotion() const
 {
     return getBuffer().get().back();
@@ -750,23 +852,19 @@ inline MotionBuffer& ProcessorMotion::getBuffer()
     return last_ptr_->getBuffer();
 }
 
-inline void ProcessorMotion::sumDeltas(CaptureMotionPtr _cap1_ptr, CaptureMotionPtr _cap2_ptr,
-                                       Eigen::VectorXs& _delta1_plus_delta2)
-{
-    Scalar dt = _cap2_ptr->getTimeStamp() - _cap1_ptr->getTimeStamp();
-    deltaPlusDelta(_cap1_ptr->getDelta(),_cap2_ptr->getDelta(), dt, _delta1_plus_delta2);
-}
-
 inline Motion ProcessorMotion::motionZero(const TimeStamp& _ts)
 {
-    return Motion(
-            {_ts,
-             deltaZero(),
-             deltaZero(),
-             Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_), // Jac
-             Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_), // Jac
-             Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_)  // Cov
-             });
+    return Motion(_ts,
+                  VectorXs::Zero(data_size_), // data
+                  Eigen::MatrixXs::Zero(data_size_, data_size_), // Cov data
+                  deltaZero(),
+                  Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_), // Cov delta
+                  deltaZero(),
+                  Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_), // Cov delta_integr
+                  Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_), // Jac delta
+                  Eigen::MatrixXs::Zero(delta_cov_size_, delta_cov_size_), // Jac delta_integr
+                  Eigen::MatrixXs::Zero(delta_cov_size_, calib_size_)      // Jac calib
+    );
 }
 
 inline CaptureBasePtr ProcessorMotion::getOriginPtr()
diff --git a/src/processor_odom_2D.cpp b/src/processor_odom_2D.cpp
index b6e03e3d6b6d32c4d34d9a15bf973ce7d8c68a96..70c5442380e3bca2f0be3402fa0322db56df833f 100644
--- a/src/processor_odom_2D.cpp
+++ b/src/processor_odom_2D.cpp
@@ -4,25 +4,28 @@ namespace wolf
 
 ProcessorBasePtr ProcessorOdom2D::create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr)
 {
-    Scalar dist_traveled_th ;
-    Scalar cov_det_th       ;
-    Scalar elapsed_time_th  ;
+
+    ProcessorOdom2DPtr prc_ptr;
+
     if (_params)
     {
         std::shared_ptr<ProcessorParamsOdom2D> params = std::static_pointer_cast<ProcessorParamsOdom2D>(_params);
-        dist_traveled_th = params->dist_traveled_th_;
-        cov_det_th       = params->cov_det_th_;
-        elapsed_time_th  = params->elapsed_time_th_;
+
+        prc_ptr = std::make_shared<ProcessorOdom2D>(params->dist_traveled_th_,
+                                                    params->theta_traveled_th_,
+                                                    params->cov_det_th_,
+                                                    params->elapsed_time_th_,
+                                                    params->unmeasured_perturbation_std_);
     }
     else
     {
-        std::cout << __FILE__ << ":" << __FUNCTION__ << "() : No parameters provided. Using dummy set." << std::endl;
-        dist_traveled_th = 1;
-        cov_det_th       = 1;
-        elapsed_time_th  = 1;
+        std::cout << __FILE__ << ":" << __FUNCTION__ << "() : No parameters provided. Using default set." << std::endl;
+
+        prc_ptr = std::make_shared<ProcessorOdom2D>();
     }
-    ProcessorOdom2DPtr prc_ptr = std::make_shared<ProcessorOdom2D>(dist_traveled_th, cov_det_th, elapsed_time_th);
+
     prc_ptr->setName(_unique_name);
+
     return prc_ptr;
 }
 
diff --git a/src/processor_odom_2D.h b/src/processor_odom_2D.h
index 07a20b155493e3232b2b26732ee78e09986abe44..be2654cf032ae7ab1484e162470e883ecb10b7f7 100644
--- a/src/processor_odom_2D.h
+++ b/src/processor_odom_2D.h
@@ -21,67 +21,89 @@ WOLF_STRUCT_PTR_TYPEDEFS(ProcessorParamsOdom2D);
 struct ProcessorParamsOdom2D : public ProcessorParamsBase
 {
     Scalar dist_traveled_th_;
+    Scalar theta_traveled_th_;
     Scalar cov_det_th_;
     Scalar elapsed_time_th_;
+    Scalar unmeasured_perturbation_std_;
 };
 
 class ProcessorOdom2D : public ProcessorMotion
 {
     public:
-        ProcessorOdom2D(const Scalar& _traveled_dist_th, const Scalar& _cov_det_th, const Scalar& _elapsed_time_th);
+        ProcessorOdom2D(const Scalar& _traveled_dist_th             = 1.0,
+                        const Scalar& _theta_traveled_th            = 0.17,
+                        const Scalar& _cov_det_th                   = 1.0,
+                        const Scalar& _elapsed_time_th              = 1.0,
+                        const Scalar& _unmeasured_perturbation_std  = 0.001);
         virtual ~ProcessorOdom2D();
         virtual bool voteForKeyFrame();
 
     protected:
         virtual void data2delta(const Eigen::VectorXs& _data,
                                 const Eigen::MatrixXs& _data_cov,
-                                const Scalar _dt);
-        void deltaPlusDelta(const Eigen::VectorXs& _delta1,
-                            const Eigen::VectorXs& _delta2,
-                            const Scalar _Dt2,
-                            Eigen::VectorXs& _delta1_plus_delta2);
-        void deltaPlusDelta(const Eigen::VectorXs& _delta1,
-                            const Eigen::VectorXs& _delta2,
-                            const Scalar _Dt2,
-                            Eigen::VectorXs& _delta1_plus_delta2,
-                            Eigen::MatrixXs& _jacobian1,
-                            Eigen::MatrixXs& _jacobian2);
-        void xPlusDelta(const Eigen::VectorXs& _x,
-                        const Eigen::VectorXs& _delta,
-                        const Scalar _Dt,
-                        Eigen::VectorXs& _x_plus_delta);
-        Eigen::VectorXs deltaZero() const;
-        Motion interpolate(const Motion& _ref,
-                           Motion& _second,
-                           TimeStamp& _ts);
+                                const Scalar _dt,
+                                Eigen::VectorXs& _delta,
+                                Eigen::MatrixXs& _delta_cov,
+                                const Eigen::VectorXs& _calib,
+                                Eigen::MatrixXs& _jacobian_calib);
+        virtual void deltaPlusDelta(const Eigen::VectorXs& _delta1,
+                                    const Eigen::VectorXs& _delta2,
+                                    const Scalar _Dt2,
+                                    Eigen::VectorXs& _delta1_plus_delta2);
+        virtual void deltaPlusDelta(const Eigen::VectorXs& _delta1,
+                                    const Eigen::VectorXs& _delta2,
+                                    const Scalar _Dt2,
+                                    Eigen::VectorXs& _delta1_plus_delta2,
+                                    Eigen::MatrixXs& _jacobian1,
+                                    Eigen::MatrixXs& _jacobian2);
+        virtual void statePlusDelta(const Eigen::VectorXs& _x,
+                                const Eigen::VectorXs& _delta,
+                                const Scalar _Dt,
+                                Eigen::VectorXs& _x_plus_delta);
+        virtual Eigen::VectorXs deltaZero() const;
+        virtual Motion interpolate(const Motion& _ref,
+                                   Motion& _second,
+                                   TimeStamp& _ts);
 
         virtual ConstraintBasePtr emplaceConstraint(FeatureBasePtr _feature_motion, FrameBasePtr _frame_origin);
-
-        virtual void resetDerived();
+        virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion, FrameBasePtr _related_frame); 
 
     protected:
         Scalar dist_traveled_th_;
+        Scalar theta_traveled_th_;
         Scalar cov_det_th_;
         Scalar elapsed_time_th_;
+        Matrix3s unmeasured_perturbation_cov_; ///< Covariance to be added to the unmeasured perturbation
 
         // Factory method
     public:
         static ProcessorBasePtr create(const std::string& _unique_name, const ProcessorParamsBasePtr _params, const SensorBasePtr sensor_ptr = nullptr);
 };
 
-inline ProcessorOdom2D::ProcessorOdom2D(const Scalar& _traveled_dist_th, const Scalar& _cov_det_th, const Scalar& _elapsed_time_th) :
+inline ProcessorOdom2D::ProcessorOdom2D(const Scalar& _dist_traveled_th,
+                                        const Scalar& _theta_traveled_th,
+                                        const Scalar& _cov_det_th,
+                                        const Scalar& _elapsed_time_th,
+                                        const Scalar& _unmeasured_perturbation_std) :
         ProcessorMotion("ODOM 2D", 3, 3, 3, 2),
-        dist_traveled_th_(_traveled_dist_th),
+        dist_traveled_th_(_dist_traveled_th),
+        theta_traveled_th_(_theta_traveled_th),
         cov_det_th_(_cov_det_th),
         elapsed_time_th_(_elapsed_time_th)
 {
-    //
+    unmeasured_perturbation_cov_ = _unmeasured_perturbation_std*_unmeasured_perturbation_std * Matrix3s::Identity();
 }
 inline ProcessorOdom2D::~ProcessorOdom2D()
 {
 }
 
-inline void ProcessorOdom2D::data2delta(const Eigen::VectorXs& _data, const Eigen::MatrixXs& _data_cov, const Scalar _dt)
+inline void ProcessorOdom2D::data2delta(const Eigen::VectorXs& _data,
+                                        const Eigen::MatrixXs& _data_cov,
+                                        const Scalar _dt,
+                                        Eigen::VectorXs& _delta,
+                                        Eigen::MatrixXs& _delta_cov,
+                                        const Eigen::VectorXs& _calib,
+                                        Eigen::MatrixXs& _jacobian_calib)
 {
     //std::cout << "ProcessorOdom2d::data2delta" << std::endl;
 
@@ -92,9 +114,9 @@ inline void ProcessorOdom2D::data2delta(const Eigen::VectorXs& _data, const Eige
     // data  is [dtheta, dr]
     // delta is [dx, dy, dtheta]
     // motion model is 1/2 turn + straight + 1/2 turn
-    delta_(0) = cos(_data(1)/2) * _data(0);
-    delta_(1) = sin(_data(1)/2) * _data(0);
-    delta_(2) = _data(1);
+    _delta(0) = cos(_data(1)/2) * _data(0);
+    _delta(1) = sin(_data(1)/2) * _data(0);
+    _delta(2) = _data(1);
 
     // Fill delta covariance
     Eigen::MatrixXs J(delta_cov_size_,data_size_);
@@ -105,34 +127,32 @@ inline void ProcessorOdom2D::data2delta(const Eigen::VectorXs& _data, const Eige
     J(1,1) =   _data(0) * cos(_data(1) / 2) / 2;
     J(2,1) =   1;
 
-    delta_cov_ = J * _data_cov * J.transpose();
+    // Since input data is size 2, and delta is size 3, the noise model must be given by:
+    // 1. Covariance of the input data:  J*Q*J.tr
+    // 2. Fix variance term to be added: var*Id
+    _delta_cov = J * _data_cov * J.transpose() + unmeasured_perturbation_cov_;
 
     //std::cout << "data      :" << _data.transpose() << std::endl;
     //std::cout << "data cov  :" << std::endl << _data_cov << std::endl;
     //std::cout << "delta     :" << delta_.transpose() << std::endl;
     //std::cout << "delta cov :" << std::endl << delta_cov_ << std::endl;
+
+    // jacobian_delta_calib_ not used in this class yet. In any case, set to zero with:
+    //    jacobian_delta_calib_.setZero();
 }
 
-inline void ProcessorOdom2D::xPlusDelta(const Eigen::VectorXs& _x, const Eigen::VectorXs& _delta, const Scalar _Dt, Eigen::VectorXs& _x_plus_delta)
+inline void ProcessorOdom2D::statePlusDelta(const Eigen::VectorXs& _x, const Eigen::VectorXs& _delta, const Scalar _Dt, Eigen::VectorXs& _x_plus_delta)
 {
 
     // This is just a frame composition in 2D
 
-    //std::cout << "ProcessorOdom2d::xPlusDelta" << std::endl;
+    //std::cout << "ProcessorOdom2d::statePlusDelta" << std::endl;
 
     assert(_x.size() == x_size_ && "Wrong _x vector size");
     assert(_x_plus_delta.size() == x_size_ && "Wrong _x_plus_delta vector size");
 
-//    std::cout << "xPlusDelta ------------------------------------" << std::endl;
-//    std::cout << "_x:     " << _x.transpose() << std::endl;
-//    std::cout << "_delta: " << _delta.transpose() << std::endl;
-//    std::cout << "_x_plus_delta: " << _x_plus_delta.transpose() << std::endl;
-
     _x_plus_delta.head<2>() = _x.head<2>() + Eigen::Rotation2Ds(_x(2)).matrix() * _delta.head<2>();
     _x_plus_delta(2) = pi2pi(_x(2) + _delta(2));
-
-//    std::cout << "-----------------------------------------------" << std::endl;
-//    std::cout << "_x_plus_delta: " << _x_plus_delta.transpose() << std::endl;
 }
 
 inline void ProcessorOdom2D::deltaPlusDelta(const Eigen::VectorXs& _delta1, const Eigen::VectorXs& _delta2, const Scalar _Dt2, Eigen::VectorXs& _delta1_plus_delta2)
@@ -144,16 +164,8 @@ inline void ProcessorOdom2D::deltaPlusDelta(const Eigen::VectorXs& _delta1, cons
     assert(_delta2.size() == delta_size_ && "Wrong _delta2 vector size");
     assert(_delta1_plus_delta2.size() == delta_size_ && "Wrong _delta1_plus_delta2 vector size");
 
-//    std::cout << "deltaPlusDelta ------------------------------------" << std::endl;
-//    std::cout << "_delta1: " << _delta1.transpose() << std::endl;
-//    std::cout << "_delta2: " << _delta2.transpose() << std::endl;
-//    std::cout << "_delta1_plus_delta2: " << _delta1_plus_delta2.transpose() << std::endl;
-
     _delta1_plus_delta2.head<2>() = _delta1.head<2>() + Eigen::Rotation2Ds(_delta1(2)).matrix() * _delta2.head<2>();
     _delta1_plus_delta2(2) = pi2pi(_delta1(2) + _delta2(2));
-
-//    std::cout << "-----------------------------------------------" << std::endl;
-//    std::cout << "_delta1_plus_delta2: " << _delta1_plus_delta2.transpose() << std::endl;
 }
 
 inline void ProcessorOdom2D::deltaPlusDelta(const Eigen::VectorXs& _delta1, const Eigen::VectorXs& _delta2,
@@ -170,11 +182,6 @@ inline void ProcessorOdom2D::deltaPlusDelta(const Eigen::VectorXs& _delta1, cons
     assert(_jacobian2.rows() == delta_cov_size_ && "Wrong _jacobian2 size");
     assert(_jacobian2.cols() == delta_cov_size_ && "Wrong _jacobian2 size");
 
-//    std::cout << "deltaPlusDelta ------------------------------------" << std::endl;
-//    std::cout << "_delta1: " << _delta1.transpose() << std::endl;
-//    std::cout << "_delta2: " << _delta2.transpose() << std::endl;
-//    std::cout << "_delta1_plus_delta2: " << _delta1_plus_delta2.transpose() << std::endl;
-
     _delta1_plus_delta2.head<2>() = _delta1.head<2>() + Eigen::Rotation2Ds(_delta1(2)).matrix() * _delta2.head<2>();
     _delta1_plus_delta2(2) = pi2pi(_delta1(2) + _delta2(2));
 
@@ -186,9 +193,6 @@ inline void ProcessorOdom2D::deltaPlusDelta(const Eigen::VectorXs& _delta1, cons
     // jac wrt delta
     _jacobian2 = Eigen::MatrixXs::Identity(delta_cov_size_,delta_cov_size_);
     _jacobian2.topLeftCorner<2,2>() = Eigen::Rotation2Ds(_delta1(2)).matrix();
-
-    //std::cout << "-----------------------------------------------" << std::endl;
-    //std::cout << "_delta1_plus_delta2: " << _delta1_plus_delta2.transpose() << std::endl;
 }
 
 inline Eigen::VectorXs ProcessorOdom2D::deltaZero() const
@@ -198,24 +202,42 @@ inline Eigen::VectorXs ProcessorOdom2D::deltaZero() const
 
 inline ConstraintBasePtr ProcessorOdom2D::emplaceConstraint(FeatureBasePtr _feature_motion, FrameBasePtr _frame_origin)
 {
-    ConstraintOdom2DPtr ctr_odom = std::make_shared<ConstraintOdom2D>(_feature_motion, _frame_origin);
+    ConstraintOdom2DPtr ctr_odom = std::make_shared<ConstraintOdom2D>(_feature_motion, _frame_origin, shared_from_this());
     _feature_motion->addConstraint(ctr_odom);
     _frame_origin->addConstrainedBy(ctr_odom);
     return ctr_odom;
 }
 
+inline FeatureBasePtr ProcessorOdom2D::emplaceFeature(CaptureMotionPtr _capture_motion, FrameBasePtr _related_frame)
+{
+    // create motion feature and add it to the key_capture
+    FeatureBasePtr key_feature_ptr = std::make_shared<FeatureBase>(
+            "ODOM 2D",
+            _capture_motion->getBuffer().get().back().delta_integr_,
+            _capture_motion->getBuffer().get().back().delta_integr_cov_);
+
+    _capture_motion->addFeature(key_feature_ptr);
+
+    return key_feature_ptr;
+}
+
 inline Motion ProcessorOdom2D::interpolate(const Motion& _ref, Motion& _second, TimeStamp& _ts)
+
 {
     // TODO: Implement actual interpolation
     // Implementation: motion ref keeps the same
     //
     Motion _interpolated(_ref);
     _interpolated.ts_                   = _ts;
+    _interpolated.data_                 = Vector3s::Zero();
+    _interpolated.data_cov_             = Matrix3s::Zero();
     _interpolated.delta_                = deltaZero();
     _interpolated.delta_cov_            = Eigen::MatrixXs::Zero(delta_size_, delta_size_);
     _interpolated.delta_integr_         = _ref.delta_integr_;
+    _interpolated.delta_integr_cov_     = _ref.delta_integr_cov_;
     _interpolated.jacobian_delta_integr_. setIdentity();
     _interpolated.jacobian_delta_       . setZero();
+    _interpolated.jacobian_calib_       . setZero();
     return _interpolated;
 }
 
@@ -230,9 +252,16 @@ inline bool ProcessorOdom2D::voteForKeyFrame()
         return true;
     }
 
+    if (/*std::abs*/(getBuffer().get().back().delta_integr_.tail<1>().norm()) > theta_traveled_th_)
+    {
+//        std::cout << "ProcessorOdom2D:: " << id() << " -  VOTE FOR KEY FRAME traveled distance "
+//                << getBuffer().get().back().delta_integr_.head<2>().norm() << std::endl;
+        return true;
+    }
+
     // Uncertainty criterion
-    delta_integrated_cov_ = getBuffer().get().back().jacobian_delta_integr_ * delta_integrated_cov_ * getBuffer().get().back().jacobian_delta_integr_.transpose() + getBuffer().get().back().jacobian_delta_ * getBuffer().get().back().delta_cov_ * getBuffer().get().back().jacobian_delta_.transpose();
-    if (delta_integrated_cov_.determinant() > cov_det_th_)
+//    delta_integrated_cov_ = getBuffer().get().back().jacobian_delta_integr_ * delta_integrated_cov_ * getBuffer().get().back().jacobian_delta_integr_.transpose() + getBuffer().get().back().jacobian_delta_ * getBuffer().get().back().delta_cov_ * getBuffer().get().back().jacobian_delta_.transpose();
+    if (getBuffer().get().back().delta_integr_cov_.determinant() > cov_det_th_)
     {
 //        std::cout << "ProcessorOdom2D:: " << id() << " - VOTE FOR KEY FRAME covariance det "
 //                << delta_integrated_cov_.determinant() << std::endl;
@@ -250,12 +279,6 @@ inline bool ProcessorOdom2D::voteForKeyFrame()
     return false;
 }
 
-inline void ProcessorOdom2D::resetDerived()
-{
-    // We want this covariance up-to-date because we use it in vote_for_keyframe().
-    delta_integrated_cov_ = integrateBufferCovariance(getBuffer());
-}
-
 } // namespace wolf
 
 #endif /* SRC_PROCESSOR_ODOM_2D_H_ */
diff --git a/src/processor_odom_3D.cpp b/src/processor_odom_3D.cpp
index 1e86bafd87086dcde60718c1a2e03dcdd3c6c15e..fada33877099dba6e1e3cca6fccd4c418fd8e9b3 100644
--- a/src/processor_odom_3D.cpp
+++ b/src/processor_odom_3D.cpp
@@ -43,15 +43,21 @@ void ProcessorOdom3D::setup(SensorOdom3DPtr sen_ptr)
     }
 }
 
-void ProcessorOdom3D::data2delta(const Eigen::VectorXs& _data, const Eigen::MatrixXs& _data_cov, const Scalar _dt)
+void ProcessorOdom3D::data2delta(const Eigen::VectorXs& _data,
+                                 const Eigen::MatrixXs& _data_cov,
+                                 const Scalar _dt,
+                                 Eigen::VectorXs& _delta,
+                                 Eigen::MatrixXs& _delta_cov,
+                                 const Eigen::VectorXs& _calib,
+                                 Eigen::MatrixXs& _jacobian_calib)
 {
     assert((_data.size() == 6 || _data.size() == 7) && "Wrong data size. Must be 6 or 7 for 3D.");
     Scalar disp, rot; // displacement and rotation of this motion step
     if (_data.size() == (long int)6)
     {
         // rotation in vector form
-        delta_.head<3>() = _data.head<3>();
-        new (&q_out_) Eigen::Map<Eigen::Quaternions>(delta_.data() + 3);
+        _delta.head<3>() = _data.head<3>();
+        new (&q_out_) Eigen::Map<Eigen::Quaternions>(_delta.data() + 3);
         q_out_ = v2q(_data.tail<3>());
         disp = _data.head<3>().norm();
         rot = _data.tail<3>().norm();
@@ -59,7 +65,7 @@ void ProcessorOdom3D::data2delta(const Eigen::VectorXs& _data, const Eigen::Matr
     else
     {
         // rotation in quaternion form
-        delta_ = _data;
+        _delta = _data;
         disp = _data.head<3>().norm();
         rot = 2 * acos(_data(3));
     }
@@ -83,7 +89,7 @@ void ProcessorOdom3D::data2delta(const Eigen::VectorXs& _data, const Eigen::Matr
     Eigen::Matrix6s data_cov(Eigen::Matrix6s::Identity());
     data_cov(0, 0) = data_cov(1, 1) = data_cov(2, 2) = disp_var;
     data_cov(3, 3) = data_cov(4, 4) = data_cov(5, 5) = rot_var;
-    delta_cov_ = data_cov;
+    _delta_cov = data_cov;
 }
 
 void ProcessorOdom3D::deltaPlusDelta(const Eigen::VectorXs& _delta1, const Eigen::VectorXs& _delta2, const Scalar _Dt2,
@@ -139,13 +145,13 @@ void ProcessorOdom3D::deltaPlusDelta(const Eigen::VectorXs& _delta1, const Eigen
     q_out_ = q1_ * q2_;
 }
 
-void ProcessorOdom3D::xPlusDelta(const Eigen::VectorXs& _x, const Eigen::VectorXs& _delta, const Scalar _Dt,
+void ProcessorOdom3D::statePlusDelta(const Eigen::VectorXs& _x, const Eigen::VectorXs& _delta, const Scalar _Dt,
                                  Eigen::VectorXs& _x_plus_delta)
-{
-    assert(_x.size() == x_size_ && "Wrong _x vector size");
+{   
+    assert(_x.size() >= x_size_ && "Wrong _x vector size"); //we need a state vector which size is at least x_size_
     assert(_delta.size() == delta_size_ && "Wrong _delta vector size");
     assert(_x_plus_delta.size() == x_size_ && "Wrong _x_plus_delta vector size");
-    remap(_x, _delta, _x_plus_delta);
+    remap(_x.head(x_size_), _delta, _x_plus_delta); //we take only the x_sixe_ first elements of the state Vectors (Position + Orientation)
     p_out_ = p1_ + q1_ * p2_;
     q_out_ = q1_ * q2_;
 }
@@ -268,10 +274,12 @@ ProcessorBasePtr ProcessorOdom3D::create(const std::string& _unique_name, const
 
 bool ProcessorOdom3D::voteForKeyFrame()
 {
-//    WOLF_DEBUG( "Time span   : " , getBuffer().get().back().ts_ - getBuffer().get().front().ts_ );
-//    WOLF_DEBUG( "BufferLength: " , getBuffer().get().size() );
-//    WOLF_DEBUG( "DistTraveled: " , delta_integrated_.head(3).norm() );
-//    WOLF_DEBUG( "AngleTurned : " , 2.0 * acos(delta_integrated_(6)) );
+    //WOLF_DEBUG( "Time span   : " , getBuffer().get().back().ts_ - getBuffer().get().front().ts_ );
+    //WOLF_DEBUG( " last ts : ", getBuffer().get().back().ts_);
+    //WOLF_DEBUG( " first ts : ", getBuffer().get().front().ts_);
+    //WOLF_DEBUG( "BufferLength: " , getBuffer().get().size() );
+    //WOLF_DEBUG( "DistTraveled: " , delta_integrated_.head(3).norm() );
+    //WOLF_DEBUG( "AngleTurned : " , 2.0 * acos(delta_integrated_(6)) );
     // time span
     if (getBuffer().get().back().ts_ - getBuffer().get().front().ts_ > max_time_span_)
     {
@@ -298,7 +306,7 @@ bool ProcessorOdom3D::voteForKeyFrame()
         WOLF_DEBUG( "PM: vote: angle turned" );
         return true;
     }
-    WOLF_DEBUG( "PM: do not vote" );
+    //WOLF_DEBUG( "PM: do not vote" );
     return false;
 }
 
diff --git a/src/processor_odom_3D.h b/src/processor_odom_3D.h
index f0ecd5174fb3efaedf7f23fbe13d9a968e9dfd61..1a806888cff43bdbb3d84684258aca9ec641f48a 100644
--- a/src/processor_odom_3D.h
+++ b/src/processor_odom_3D.h
@@ -73,7 +73,11 @@ class ProcessorOdom3D : public ProcessorMotion
     public:
         virtual void data2delta(const Eigen::VectorXs& _data,
                                 const Eigen::MatrixXs& _data_cov,
-                                const Scalar _dt);
+                                const Scalar _dt,
+                                Eigen::VectorXs& _delta,
+                                Eigen::MatrixXs& _delta_cov,
+                                const Eigen::VectorXs& _calib,
+                                Eigen::MatrixXs& _jacobian_calib);
         void deltaPlusDelta(const Eigen::VectorXs& _delta1,
                             const Eigen::VectorXs& _delta2,
                             const Scalar _Dt2,
@@ -84,7 +88,7 @@ class ProcessorOdom3D : public ProcessorMotion
                             Eigen::VectorXs& _delta1_plus_delta2,
                             Eigen::MatrixXs& _jacobian1,
                             Eigen::MatrixXs& _jacobian2);
-        void xPlusDelta(const Eigen::VectorXs& _x,
+        void statePlusDelta(const Eigen::VectorXs& _x,
                         const Eigen::VectorXs& _delta,
                         const Scalar _Dt,
                         Eigen::VectorXs& _x_plus_delta);
@@ -93,8 +97,10 @@ class ProcessorOdom3D : public ProcessorMotion
                            Motion& _motion,
                            TimeStamp& _ts);
         bool voteForKeyFrame();
-        ConstraintBasePtr emplaceConstraint(FeatureBasePtr _feature_motion,
+        virtual ConstraintBasePtr emplaceConstraint(FeatureBasePtr _feature_motion,
                                            FrameBasePtr _frame_origin);
+        virtual FeatureBasePtr emplaceFeature(CaptureMotionPtr _capture_motion, 
+                                            FrameBasePtr _related_frame);        
 
     protected:
         // noise parameters (stolen from owner SensorOdom3D)
@@ -132,12 +138,24 @@ inline Eigen::VectorXs ProcessorOdom3D::deltaZero() const
 inline ConstraintBasePtr ProcessorOdom3D::emplaceConstraint(FeatureBasePtr _feature_motion,
                                                            FrameBasePtr _frame_origin)
 {
-    ConstraintOdom3DPtr ctr_odom = std::make_shared<ConstraintOdom3D>(_feature_motion, _frame_origin);
+    ConstraintOdom3DPtr ctr_odom = std::make_shared<ConstraintOdom3D>(_feature_motion, _frame_origin, shared_from_this());
     _feature_motion->addConstraint(ctr_odom);
     _frame_origin->addConstrainedBy(ctr_odom);
     return ctr_odom;
 }
 
+inline FeatureBasePtr ProcessorOdom3D::emplaceFeature(CaptureMotionPtr _capture_motion, FrameBasePtr _related_frame)
+{
+    // create motion feature and add it to the key_capture
+    FeatureBasePtr key_feature_ptr = std::make_shared<FeatureBase>(
+            "ODOM 3D",
+            _capture_motion->getBuffer().get().back().delta_integr_,
+            _capture_motion->getBuffer().get().back().delta_integr_cov_);
+    _capture_motion->addFeature(key_feature_ptr);
+
+    return key_feature_ptr;
+}
+
 inline void ProcessorOdom3D::remap(const Eigen::VectorXs& _x1,
                                    const Eigen::VectorXs& _x2,
                                    Eigen::VectorXs& _x_out)
diff --git a/src/processor_tracker_feature_corner.cpp b/src/processor_tracker_feature_corner.cpp
index 584023b4a2f2d4c13c707f3482b839d1368f8b16..dbf96c0f75131ae9fc5935259ada7a088563bcd6 100644
--- a/src/processor_tracker_feature_corner.cpp
+++ b/src/processor_tracker_feature_corner.cpp
@@ -96,7 +96,7 @@ ConstraintBasePtr ProcessorTrackerFeatureCorner::createConstraint(FeatureBasePtr
     // Getting landmark ptr
     LandmarkCorner2DPtr landmark_ptr = nullptr;
     for (auto constraint : _feature_other_ptr->getConstraintList())
-        if (constraint->getLandmarkOtherPtr() != nullptr && constraint->getLandmarkOtherPtr()->getType() == "CORNER")
+        if (constraint->getLandmarkOtherPtr() != nullptr && constraint->getLandmarkOtherPtr()->getType() == "CORNER 2D")
             landmark_ptr = std::static_pointer_cast<LandmarkCorner2D>(constraint->getLandmarkOtherPtr());
 
     if (landmark_ptr == nullptr)
@@ -108,13 +108,13 @@ ConstraintBasePtr ProcessorTrackerFeatureCorner::createConstraint(FeatureBasePtr
                                                           _feature_ptr->getMeasurement()(3));
 
         // Add landmark constraint to the other feature
-        _feature_other_ptr->addConstraint(std::make_shared<ConstraintCorner2D>(_feature_other_ptr, landmark_ptr));
+        _feature_other_ptr->addConstraint(std::make_shared<ConstraintCorner2D>(_feature_other_ptr, landmark_ptr, shared_from_this()));
     }
 
 //    std::cout << "creating constraint: last feature " << _feature_ptr->getMeasurement()
 //              << " with origin feature " << _feature_other_ptr->getMeasurement() << std::endl
 //              << " corresponding to landmark " << landmark_ptr->id() << std::endl;
-    return std::make_shared<ConstraintCorner2D>(_feature_ptr, landmark_ptr);
+    return std::make_shared<ConstraintCorner2D>(_feature_ptr, landmark_ptr, shared_from_this());
 }
 
 void ProcessorTrackerFeatureCorner::extractCorners(CaptureLaser2DPtr _capture_laser_ptr,
diff --git a/src/processor_tracker_feature_dummy.h b/src/processor_tracker_feature_dummy.h
index 597bac8ead44adcbd334c5b7c2a3871a5821360f..5eb244498fff834ebad6951f975ed802ff4595dd 100644
--- a/src/processor_tracker_feature_dummy.h
+++ b/src/processor_tracker_feature_dummy.h
@@ -93,11 +93,11 @@ inline bool ProcessorTrackerFeatureDummy::correctFeatureDrift(const FeatureBaseP
 inline ConstraintBasePtr ProcessorTrackerFeatureDummy::createConstraint(FeatureBasePtr _feature_ptr,
                                                                       FeatureBasePtr _feature_other_ptr)
 {
-    std::cout << "creating constraint: last feature " << _feature_ptr->getMeasurement()
-              << " with origin feature " << _feature_other_ptr->getMeasurement() << std::endl;
-  auto ctr = std::make_shared<ConstraintEpipolar>(_feature_ptr, _feature_other_ptr);
-    _feature_ptr->addConstraint(ctr);
-    _feature_other_ptr->addConstrainedBy(ctr);
+//    std::cout << "creating constraint: last feature " << _feature_ptr->getMeasurement()
+//              << " with origin feature " << _feature_other_ptr->getMeasurement() << std::endl;
+    auto ctr = std::make_shared<ConstraintEpipolar>(_feature_ptr, _feature_other_ptr, shared_from_this());
+//    _feature_ptr->addConstraint(ctr);
+//    _feature_other_ptr->addConstrainedBy(ctr);
     return ctr;
 }
 
diff --git a/src/processor_tracker_landmark_corner.cpp b/src/processor_tracker_landmark_corner.cpp
index e0522989cbb1f55a114c99bd854c8d54e296ca7a..384034534409278e1984e7d015b9515a40edb300 100644
--- a/src/processor_tracker_landmark_corner.cpp
+++ b/src/processor_tracker_landmark_corner.cpp
@@ -64,7 +64,7 @@ unsigned int ProcessorTrackerLandmarkCorner::findLandmarks(const LandmarkBaseLis
         Scalar closest_dm2 = 1e3;
         for (auto landmark_it = not_matched_landmarks.begin(); landmark_it != not_matched_landmarks.end(); landmark_it++)
         {
-            if ((*landmark_it)->getType() == "CORNER" &&
+            if ((*landmark_it)->getType() == "CORNER 2D" &&
                 fabs(pi2pi((std::static_pointer_cast<FeatureCorner2D>(*feature_it))->getAperture() - (*landmark_it)->getDescriptor(0))) < aperture_error_th_)
             {
                 dm2 = computeSquaredMahalanobisDistances((*feature_it), expected_features[*landmark_it],
@@ -128,7 +128,7 @@ unsigned int ProcessorTrackerLandmarkCorner::findLandmarks(const LandmarkBaseLis
             for (auto landmark_it = _landmarks_corner_searched.begin(); landmark_it != _landmarks_corner_searched.end();
                     landmark_it++, jj++)
             {
-                if ((*landmark_it)->getType() == "CORNER")
+                if ((*landmark_it)->getType() == "CORNER 2D")
                 {
                     landmarks_map[jj] = landmark_it;
                     landmarks_index_map[jj] = 0;
diff --git a/src/processor_tracker_landmark_corner.h b/src/processor_tracker_landmark_corner.h
index c4469f418a48e51278add6274ff618ba62046a1e..80acb3c30ce066391143ac2c658741defee6398a 100644
--- a/src/processor_tracker_landmark_corner.h
+++ b/src/processor_tracker_landmark_corner.h
@@ -221,7 +221,7 @@ inline ConstraintBasePtr ProcessorTrackerLandmarkCorner::createConstraint(Featur
 {
     assert(_feature_ptr != nullptr && _landmark_ptr != nullptr && "ProcessorTrackerLandmarkCorner::createConstraint: feature and landmark pointers can not be nullptr!");
 
-    return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>((_landmark_ptr)));
+    return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>((_landmark_ptr)), shared_from_this());
 }
 
 } // namespace wolf
diff --git a/src/processor_tracker_landmark_dummy.cpp b/src/processor_tracker_landmark_dummy.cpp
index 60b22ac304b86a5dae72e78d59bfa54b88116ec5..71051458bfdd9ef5b5f4013984e20de93c4370b8 100644
--- a/src/processor_tracker_landmark_dummy.cpp
+++ b/src/processor_tracker_landmark_dummy.cpp
@@ -88,7 +88,7 @@ ConstraintBasePtr ProcessorTrackerLandmarkDummy::createConstraint(FeatureBasePtr
     std::cout << "\tProcessorTrackerLandmarkDummy::createConstraint" << std::endl;
     std::cout << "\t\tfeature " << _feature_ptr->getMeasurement() << std::endl;
     std::cout << "\t\tlandmark "<< _landmark_ptr->getDescriptor() << std::endl;
-    return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>(_landmark_ptr) );
+    return std::make_shared<ConstraintCorner2D>(_feature_ptr, std::static_pointer_cast<LandmarkCorner2D>(_landmark_ptr), shared_from_this());
 }
 
 } //namespace wolf
diff --git a/src/processor_tracker_landmark_polyline.cpp b/src/processor_tracker_landmark_polyline.cpp
index 74a37dac155e1280514dce655d7fc5963cc8c6ad..db749cfb1e5c7ac443604846ddbba76c73f2770e 100644
--- a/src/processor_tracker_landmark_polyline.cpp
+++ b/src/processor_tracker_landmark_polyline.cpp
@@ -816,7 +816,8 @@ void ProcessorTrackerLandmarkPolyline::establishConstraints()
                 if (lmk_next_point_id > polyline_landmark->getLastId())
                     lmk_next_point_id -= polyline_landmark->getNPoints();
                 //std::cout << "point-line: landmark points " << lmk_point_id << ", " << lmk_next_point_id << std::endl;
-                last_feature->addConstraint(std::make_shared<ConstraintPointToLine2D>(polyline_feature, polyline_landmark, ftr_point_id, lmk_point_id, lmk_next_point_id));
+                last_feature->addConstraint(std::make_shared<ConstraintPointToLine2D>(polyline_feature, polyline_landmark, shared_from_this(),
+                                                                                      ftr_point_id, lmk_point_id, lmk_next_point_id));
                 //std::cout << "constraint added" << std::endl;
             }
 
@@ -828,7 +829,8 @@ void ProcessorTrackerLandmarkPolyline::establishConstraints()
                 if (lmk_prev_point_id < polyline_landmark->getFirstId())
                     lmk_prev_point_id += polyline_landmark->getNPoints();
                 //std::cout << "point-line: landmark points " << lmk_point_id << ", " << lmk_prev_point_id << std::endl;
-                last_feature->addConstraint(std::make_shared<ConstraintPointToLine2D>(polyline_feature, polyline_landmark, ftr_point_id, lmk_point_id, lmk_prev_point_id));
+                last_feature->addConstraint(std::make_shared<ConstraintPointToLine2D>(polyline_feature, polyline_landmark, shared_from_this(),
+                                                                                      ftr_point_id, lmk_point_id, lmk_prev_point_id));
                 //std::cout << "constraint added" << std::endl;
             }
 
@@ -840,7 +842,8 @@ void ProcessorTrackerLandmarkPolyline::establishConstraints()
 				//std::cout << "landmark first id:" << polyline_landmark->getFirstId() << std::endl;
 				//std::cout << "landmark last id:" << polyline_landmark->getLastId() << std::endl;
 				//std::cout << "landmark n points:" << polyline_landmark->getNPoints() << std::endl;
-                last_feature->addConstraint(std::make_shared<ConstraintPoint2D>(polyline_feature, polyline_landmark, ftr_point_id, lmk_point_id));
+                last_feature->addConstraint(std::make_shared<ConstraintPoint2D>(polyline_feature, polyline_landmark, shared_from_this(),
+                                                                                ftr_point_id, lmk_point_id));
                 //std::cout << "constraint added" << std::endl;
             }
         }
diff --git a/src/rotations.h b/src/rotations.h
index 6b5605ea6d4db0d5ba655b2f98c3a4b60de782de..9160256067eae0ba5d2ce8020ca951f31add6b9a 100644
--- a/src/rotations.h
+++ b/src/rotations.h
@@ -381,6 +381,19 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_left_inv(const Eige
     return Eigen::Matrix<T, 3, 3>::Identity() - (T)0.5 * W + M; //is this really more optimized?
 }
 
+template<typename T>
+inline Eigen::Matrix<T, 3, 3> matrixRollPitchYaw(const T roll,
+                                                 const T pitch,
+                                                 const T yaw)
+{
+  const Eigen::AngleAxis<T> ax = Eigen::AngleAxis<T>(roll,  Eigen::Matrix<T, 3, 1>::UnitX());
+  const Eigen::AngleAxis<T> ay = Eigen::AngleAxis<T>(pitch, Eigen::Matrix<T, 3, 1>::UnitY());
+  const Eigen::AngleAxis<T> az = Eigen::AngleAxis<T>(yaw,   Eigen::Matrix<T, 3, 1>::UnitZ());
+
+  return (az * ay * ax).toRotationMatrix().matrix();
+}
+
+
 } // namespace wolf
 
 #endif /* ROTATIONS_H_ */
diff --git a/src/sensor_base.cpp b/src/sensor_base.cpp
index 8ebe7bc40edfa84212d80720387393a8dd6df258..7862208791bea5f7cd86d3594da70b3458e60424 100644
--- a/src/sensor_base.cpp
+++ b/src/sensor_base.cpp
@@ -6,14 +6,20 @@ namespace wolf {
 
 unsigned int SensorBase::sensor_id_count_ = 0;
 
-SensorBase::SensorBase(const std::string& _type, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _intr_ptr,
-                       const unsigned int _noise_size, const bool _extr_dyn) :
+SensorBase::SensorBase(const std::string& _type,
+                       StateBlockPtr _p_ptr,
+                       StateBlockPtr _o_ptr,
+                       StateBlockPtr _intr_ptr,
+                       const unsigned int _noise_size,
+                       const bool _extr_dyn,
+                       const bool _intr_dyn) :
         NodeBase("SENSOR", _type),
         hardware_ptr_(),
         state_block_vec_(3), // allow for 3 state blocks by default. Resize in derived constructors if needed.
         is_removing_(false),
         sensor_id_(++sensor_id_count_), // simple ID factory
         extrinsic_dynamic_(_extr_dyn),
+        intrinsic_dynamic_(_intr_dyn),
         noise_std_(_noise_size),
         noise_cov_(_noise_size, _noise_size)
 {
@@ -24,14 +30,20 @@ SensorBase::SensorBase(const std::string& _type, StateBlockPtr _p_ptr, StateBloc
     //
 }
 
-SensorBase::SensorBase(const std::string& _type, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _intr_ptr,
-                       const Eigen::VectorXs & _noise_std, const bool _extr_dyn) :
+SensorBase::SensorBase(const std::string& _type,
+                       StateBlockPtr _p_ptr,
+                       StateBlockPtr _o_ptr,
+                       StateBlockPtr _intr_ptr,
+                       const Eigen::VectorXs & _noise_std,
+                       const bool _extr_dyn,
+                       const bool _intr_dyn) :
         NodeBase("SENSOR", _type),
         hardware_ptr_(),
         state_block_vec_(6), // allow for 3 state blocks by default. Resize in derived constructors if needed.
         is_removing_(false),
         sensor_id_(++sensor_id_count_), // simple ID factory
         extrinsic_dynamic_(_extr_dyn),
+        intrinsic_dynamic_(_intr_dyn),
         noise_std_(_noise_std),
         noise_cov_(_noise_std.size(), _noise_std.size())
 {
diff --git a/src/sensor_base.h b/src/sensor_base.h
index 71c38883217b46077f894a3d4b00d2c4ea459f45..007580f8d2ccbcd463224858d05a7a15eb330319 100644
--- a/src/sensor_base.h
+++ b/src/sensor_base.h
@@ -23,8 +23,11 @@ namespace wolf {
  */
 struct IntrinsicsBase
 {
-        std::string type;
-        std::string name;
+  IntrinsicsBase()          = default;
+  virtual ~IntrinsicsBase() = default;
+
+  std::string type;
+  std::string name;
 };
 
 class SensorBase : public NodeBase, public std::enable_shared_from_this<SensorBase>
@@ -41,6 +44,7 @@ class SensorBase : public NodeBase, public std::enable_shared_from_this<SensorBa
         unsigned int sensor_id_;   // sensor ID
 
         bool extrinsic_dynamic_;// extrinsic parameters vary with time? If so, they will be taken from the Capture nodes. TODO: Not Yet Implemented.
+        bool intrinsic_dynamic_;// intrinsic parameters vary with time? If so, they will be taken from the Capture nodes. TODO: Not Yet Implemented.
 
         Eigen::VectorXs noise_std_; // std of sensor noise
         Eigen::MatrixXs noise_cov_; // cov matrix of noise
@@ -57,7 +61,13 @@ class SensorBase : public NodeBase, public std::enable_shared_from_this<SensorBa
          * \param _extr_dyn Flag indicating if extrinsics are dynamic (moving) or static (not moving)
          *
          **/
-        SensorBase(const std::string& _type, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _intr_ptr, const unsigned int _noise_size, const bool _extr_dyn = false);
+        SensorBase(const std::string& _type,
+                   StateBlockPtr _p_ptr,
+                   StateBlockPtr _o_ptr,
+                   StateBlockPtr _intr_ptr,
+                   const unsigned int _noise_size,
+                   const bool _extr_dyn = false,
+                   const bool _intr_dyn = false);
 
         /** \brief Constructor with noise std vector
          *
@@ -70,7 +80,14 @@ class SensorBase : public NodeBase, public std::enable_shared_from_this<SensorBa
          * \param _extr_dyn Flag indicating if extrinsics are dynamic (moving) or static (not moving)
          *
          **/
-        SensorBase(const std::string& _type, StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _intr_ptr, const Eigen::VectorXs & _noise_std, const bool _extr_dyn = false);
+        SensorBase(const std::string& _type,
+                   StateBlockPtr _p_ptr,
+                   StateBlockPtr _o_ptr,
+                   StateBlockPtr _intr_ptr,
+                   const Eigen::VectorXs & _noise_std,
+                   const bool _extr_dyn = false,
+                   const bool _intr_dyn = false);
+
         virtual ~SensorBase();
         void remove();
 
@@ -242,9 +259,11 @@ inline void SensorBase::setHardwarePtr(const HardwareBasePtr _hw_ptr)
 
 inline bool SensorBase::process(const CaptureBasePtr capture_ptr)
 {
+  if (capture_ptr == nullptr) return false;
+
   capture_ptr->setSensorPtr(shared_from_this());
 
-  for (const auto processor : processor_list_)
+  for (const auto& processor : processor_list_)
   {
     processor->process(capture_ptr);
   }
diff --git a/src/sensor_camera.cpp b/src/sensor_camera.cpp
index c22c1319f4557706deaadba44401b222cfd8beda..79e6ae700af7062fc2926027cae76b5192877813 100644
--- a/src/sensor_camera.cpp
+++ b/src/sensor_camera.cpp
@@ -57,12 +57,12 @@ SensorBasePtr SensorCamera::create(const std::string& _unique_name, //
     SensorCameraPtr sen_ptr = std::make_shared<SensorCamera>(_extrinsics_pq, intrinsics_ptr);
     sen_ptr->setName(_unique_name);
 
-//    std::cout << "Created camera:\n\tintrinsics   : " << sen_ptr->getIntrinsicPtr()->getVector().transpose() << std::endl;
+//    std::cout << "Created camera:\n\tintrinsics   : " << sen_ptr->getIntrinsicPtr()->getState().transpose() << std::endl;
 //    std::cout << "\tintrinsic matrix  : " << K_ << std::endl;
 //    std::cout << "\tdistortion  : " << distortion_.transpose() << std::endl;
 //    std::cout << "\tcorrection  : " << correction_.transpose() << std::endl;
-//    std::cout << "\tposition     : " << sen_ptr->getPPtr()->getVector().transpose() << std::endl;
-//    std::cout << "\torientation  : " << sen_ptr->getOPtr()->getVector().transpose() << std::endl;
+//    std::cout << "\tposition     : " << sen_ptr->getPPtr()->getState().transpose() << std::endl;
+//    std::cout << "\torientation  : " << sen_ptr->getOPtr()->getState().transpose() << std::endl;
 
     return sen_ptr;
 }
diff --git a/src/sensor_factory.h b/src/sensor_factory.h
index 0f503e423ef82481dac1df3918fc1a3b7ac16d48..abdba1e604a199b81b8a32c765c98197bdd87ff3 100644
--- a/src/sensor_factory.h
+++ b/src/sensor_factory.h
@@ -219,8 +219,8 @@ inline std::string SensorFactory::getClass()
 }
 
 #define WOLF_REGISTER_SENSOR(SensorType, SensorName) \
-  namespace{ const bool SensorName##Registered = \
-    SensorFactory::get().registerCreator(SensorType, SensorName::create); }\
+  namespace{ const bool WOLF_UNUSED SensorName##Registered = \
+    wolf::SensorFactory::get().registerCreator(SensorType, SensorName::create); }\
 
 } /* namespace wolf */
 
diff --git a/src/sensor_imu.cpp b/src/sensor_imu.cpp
index 21f53c61f58870ba73e7495485662e81c9cf638e..dfd50a29e203951ca8c47e423dc5f2bedeb53071 100644
--- a/src/sensor_imu.cpp
+++ b/src/sensor_imu.cpp
@@ -5,12 +5,25 @@
 
 namespace wolf {
 
-SensorIMU::SensorIMU(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _a_w_biases_ptr) :
-        SensorBase("IMU", _p_ptr, _o_ptr, _a_w_biases_ptr, 6)
+SensorIMU::SensorIMU(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr) :
+        SensorBase("IMU", _p_ptr, _o_ptr, nullptr, 6)
 {
     //
 }
 
+SensorIMU::SensorIMU(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, IntrinsicsIMUPtr params) :
+        SensorBase("IMU", _p_ptr, _o_ptr, nullptr, (Eigen::Vector6s()<<params->a_noise,params->a_noise,params->a_noise,params->w_noise,params->w_noise,params->w_noise).finished()),
+        w_noise(params->w_noise),
+        a_noise(params->a_noise),
+        ab_initial_stdev(params->ab_initial_stdev),
+        wb_initial_stdev(params->wb_initial_stdev),
+        ab_rate_stdev(params->ab_rate_stdev),
+        wb_rate_stdev(params->wb_rate_stdev)
+{
+    //
+}
+
+
 SensorIMU::~SensorIMU()
 {
     //
@@ -25,9 +38,9 @@ SensorBasePtr SensorIMU::create(const std::string& _unique_name, const Eigen::Ve
 
     StateBlockPtr pos_ptr  = std::make_shared<StateBlock>(_extrinsics_pq.head(3), true);
     StateBlockPtr ori_ptr  = std::make_shared<StateQuaternion>(_extrinsics_pq.tail(4), true);
-    StateBlockPtr bias_ptr = std::make_shared<StateBlock>(6, false); // We'll have the IMU biases here
 
-    SensorIMUPtr sen = std::make_shared<SensorIMU>(pos_ptr, ori_ptr, bias_ptr);
+    IntrinsicsIMUPtr params = std::static_pointer_cast<IntrinsicsIMU>(_intrinsics);
+    SensorIMUPtr sen = std::make_shared<SensorIMU>(pos_ptr, ori_ptr, params);
     sen->setName(_unique_name);
     return sen;
 }
diff --git a/src/sensor_imu.h b/src/sensor_imu.h
index c81d1047dd00fe97bf5bf13f766ad7ae9d9eb9e1..a3b03f5653b52bff278c93e30efb9fae5a5a4f53 100644
--- a/src/sensor_imu.h
+++ b/src/sensor_imu.h
@@ -3,12 +3,37 @@
 
 //wolf includes
 #include "sensor_base.h"
+#include <iostream>
 
 namespace wolf {
 
+WOLF_STRUCT_PTR_TYPEDEFS(IntrinsicsIMU);
+
+//TODO : bias_ptr defined as intrinsics StateBlock in constructor (see SensorBase) but here we also have another intrinsics
+//       This is confusing.
+
 struct IntrinsicsIMU : public IntrinsicsBase
 {
-        // add IMU parameters here
+        //noise std dev
+        wolf::Scalar w_noise; //standard deviation of Gyroscope noise (same for all the axis) in rad/sec/ sqrt(s)
+        wolf::Scalar a_noise; //standard deviation of Acceleration noise (same for all the axis) in m/s2/sqrt(s)
+
+        //Initial biases std dev
+        wolf::Scalar ab_initial_stdev; //accelerometer micro_g/sec
+        wolf::Scalar wb_initial_stdev; //gyroscope rad/sec
+
+        // bias rate of change std dev
+        Scalar ab_rate_stdev;
+        Scalar wb_rate_stdev;
+
+        IntrinsicsIMU() :
+            w_noise(0.001),
+            a_noise(0.04),
+            ab_initial_stdev(0.00001),
+            wb_initial_stdev(0.00001),
+            ab_rate_stdev(0.00001),
+            wb_rate_stdev(0.00001)
+        {}
 };
 
 WOLF_PTR_TYPEDEFS(SensorIMU);
@@ -17,7 +42,14 @@ class SensorIMU : public SensorBase
 {
 
     protected:
-        //add IMU parameters here
+        wolf::Scalar w_noise; //Rate Noise Spectral Density (same for all the axis) in deg/sec/ sqrt(Hz)
+        wolf::Scalar a_noise; //Power Spectral Density (same for all the axis) in micro_g/ sqrt(Hz)
+
+        //This is a trial to constraint how much can the bias change in 1 sec at most
+        wolf::Scalar ab_initial_stdev; //accelerometer micro_g/sec
+        wolf::Scalar wb_initial_stdev; //gyroscope rad/sec
+        wolf::Scalar ab_rate_stdev; //accelerometer micro_g/sec
+        wolf::Scalar wb_rate_stdev; //gyroscope rad/sec
 
     public:
         /** \brief Constructor with arguments
@@ -28,7 +60,25 @@ class SensorIMU : public SensorBase
          * \param _a_w_biases_ptr StateBlock pointer to the vector of acc and gyro biases
          *
          **/
-        SensorIMU(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, StateBlockPtr _a_w_biases_ptr = nullptr);
+        SensorIMU(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr);
+
+        /** \brief Constructor with arguments
+         *
+         * Constructor with arguments
+         * \param _p_ptr StateBlock pointer to the sensor position wrt vehicle base
+         * \param _o_ptr StateBlock pointer to the sensor orientation wrt vehicle base
+         * \param params IntrinsicsIMU pointer to sensor properties
+         * \param _a_w_biases_ptr StateBlock pointer to the vector of acc and gyro biases
+         *
+         **/
+        SensorIMU(StateBlockPtr _p_ptr, StateBlockPtr _o_ptr, IntrinsicsIMUPtr params);
+
+        Scalar getGyroNoise() const;
+        Scalar getAccelNoise() const;
+        Scalar getWbInitialStdev() const;
+        Scalar getAbInitialStdev() const;
+        Scalar getWbRateStdev() const;
+        Scalar getAbRateStdev() const;
 
         virtual ~SensorIMU();
 
@@ -37,6 +87,36 @@ class SensorIMU : public SensorBase
 
 };
 
+inline Scalar SensorIMU::getGyroNoise() const
+{
+    return w_noise;
+}
+
+inline Scalar SensorIMU::getAccelNoise() const
+{
+    return a_noise;
+}
+
+inline Scalar SensorIMU::getWbInitialStdev() const
+{
+    return wb_initial_stdev;
+}
+
+inline Scalar SensorIMU::getAbInitialStdev() const
+{
+    return ab_initial_stdev;
+}
+
+inline Scalar SensorIMU::getWbRateStdev() const
+{
+    return wb_rate_stdev;
+}
+
+inline Scalar SensorIMU::getAbRateStdev() const
+{
+    return ab_rate_stdev;
+}
+
 } // namespace wolf
 
 #endif // SENSOR_IMU_H
diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt
index 60adf7285b63d8a1e12ef3df5d1ea478bee0c8c6..16c5c81109af12da0814be69dbe0f3713e7892ff 100644
--- a/src/test/CMakeLists.txt
+++ b/src/test/CMakeLists.txt
@@ -56,6 +56,10 @@ target_link_libraries(gtest_feature_base ${PROJECT_NAME})
 wolf_add_gtest(gtest_frame_base gtest_frame_base.cpp)
 target_link_libraries(gtest_frame_base ${PROJECT_NAME})
 
+# IMU tools test
+wolf_add_gtest(gtest_imu_tools gtest_imu_tools.cpp)
+# target_link_libraries(gtest_imu_tools ${PROJECT_NAME}) // WOLF library not needed
+
 # LocalParametrizationXxx classes test
 wolf_add_gtest(gtest_local_param gtest_local_param.cpp)
 target_link_libraries(gtest_local_param ${PROJECT_NAME})
@@ -64,10 +68,6 @@ target_link_libraries(gtest_local_param ${PROJECT_NAME})
 wolf_add_gtest(gtest_motion_buffer gtest_motion_buffer.cpp)
 target_link_libraries(gtest_motion_buffer ${PROJECT_NAME})
 
-# Problem class test
-wolf_add_gtest(gtest_problem gtest_problem.cpp)
-target_link_libraries(gtest_problem ${PROJECT_NAME})
-
 # Rotation test
 wolf_add_gtest(gtest_rotation gtest_rotation.cpp)
 target_link_libraries(gtest_rotation ${PROJECT_NAME})
@@ -90,10 +90,26 @@ target_link_libraries(gtest_constraint_fix_3D ${PROJECT_NAME})
 wolf_add_gtest(gtest_constraint_fix gtest_constraint_fix.cpp)
 target_link_libraries(gtest_constraint_fix ${PROJECT_NAME})
 
+# ConstraintIMU test
+wolf_add_gtest(gtest_constraint_imu gtest_constraint_imu.cpp)
+target_link_libraries(gtest_constraint_imu ${PROJECT_NAME})
+
 # ConstraintOdom3D class test
 wolf_add_gtest(gtest_constraint_odom_3D gtest_constraint_odom_3D.cpp)
 target_link_libraries(gtest_constraint_odom_3D ${PROJECT_NAME})
 
+# FeatureIMU test
+wolf_add_gtest(gtest_feature_imu gtest_feature_imu.cpp)
+target_link_libraries(gtest_feature_imu ${PROJECT_NAME})
+
+# FrameIMU class test
+wolf_add_gtest(gtest_frame_imu gtest_frame_imu.cpp)
+target_link_libraries(gtest_frame_imu ${PROJECT_NAME})
+
+# IMU Bias + estimation tests
+#wolf_add_gtest(gtest_imuBias gtest_imuBias.cpp)
+#target_link_libraries(gtest_imuBias ${PROJECT_NAME})
+
 # Pinhole test
 wolf_add_gtest(gtest_pinhole gtest_pinhole.cpp)
 target_link_libraries(gtest_pinhole ${PROJECT_NAME})
@@ -102,6 +118,14 @@ target_link_libraries(gtest_pinhole ${PROJECT_NAME})
 wolf_add_gtest(gtest_processor_imu gtest_processor_imu.cpp)
 target_link_libraries(gtest_processor_imu ${PROJECT_NAME})
 
+# ProcessorIMU_jacobians test
+wolf_add_gtest(gtest_processorIMU_jacobians gtest_processorIMU_jacobians.cpp)
+target_link_libraries(gtest_processorIMU_jacobians ${PROJECT_NAME})
+
+# Ceres ProcessorMotion solver tests
+#wolf_add_gtest(gtest_processorMotion_optimization_testCase gtest_processorMotion_optimization_testCase.cpp)
+#target_link_libraries(gtest_processorMotion_optimization_testCase ${PROJECT_NAME})
+
 # ProcessorMotion in 2D
 wolf_add_gtest(gtest_odom_2D gtest_odom_2D.cpp)
 target_link_libraries(gtest_odom_2D ${PROJECT_NAME})
@@ -110,13 +134,16 @@ target_link_libraries(gtest_odom_2D ${PROJECT_NAME})
 wolf_add_gtest(gtest_odom_3D gtest_odom_3D.cpp)
 target_link_libraries(gtest_odom_3D ${PROJECT_NAME})
 
-IF(OpenCV_FOUND)
-	# ROI test
-	wolf_add_gtest(gtest_roi_ORB gtest_roi_ORB.cpp)
-	target_link_libraries(gtest_roi_ORB ${PROJECT_NAME})
-ENDIF(OpenCV_FOUND)
-
 # ConstraintAutodiff class test
 wolf_add_gtest(gtest_constraint_autodiff gtest_constraint_autodiff.cpp)
 target_link_libraries(gtest_constraint_autodiff ${PROJECT_NAME})
 
+# ROI test
+IF(OpenCV_FOUND)
+  # Problem class test
+  wolf_add_gtest(gtest_problem gtest_problem.cpp)
+  target_link_libraries(gtest_problem ${PROJECT_NAME})
+
+  wolf_add_gtest(gtest_roi_ORB gtest_roi_ORB.cpp)
+  target_link_libraries(gtest_roi_ORB ${PROJECT_NAME})
+ENDIF(OpenCV_FOUND)
diff --git a/src/test/data/IMU/data_check_BiasedNoisyComplex.txt b/src/test/data/IMU/data_check_BiasedNoisyComplex.txt
new file mode 100644
index 0000000000000000000000000000000000000000..c8178c207072317f5409b06bb3062488d8884133
--- /dev/null
+++ b/src/test/data/IMU/data_check_BiasedNoisyComplex.txt
@@ -0,0 +1,6008 @@
+0.0000000000000000	0.0000000000000000	0.0000000000000000	1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0600000000000000	0.0250000000000000	-0.0033000000000000	0.0450000000000000	-0.0270000000000000	0.0800000000000000	
+0.0283548783691341	-0.0102522795166149	0.0114827849097026	0.9999999999999779	0.0000000000000009	-0.0000000000000005	-0.0000000000000015	0.0020118474256471	0.0014919577993129	-0.0035148300829775	
+0.0000000000000000	0.0643372210073020	0.0428554033244972	9.8083350494535999	-0.1105191847539075	-0.2865888082234733	0.1408955391750495	
+0.0010000000000000	0.0486162385249274	0.0428006049339361	9.7965041736142595	0.0123512875994300	0.1720418395108178	0.0225937540029841	
+0.0020000000000000	0.0625472046899103	0.0096850999775399	9.8054460676130937	0.1421048177765042	-0.0559764233592714	0.0497326755435701	
+0.0030000000000000	0.0512155937171693	-0.0141077453117239	9.7836098022924372	0.3253603110506254	0.0687635167395981	0.1397442725152843	
+0.0040000000000000	0.0586549949130479	0.0170239145673337	9.7871714267562666	-0.0519956998469767	-0.1034132000625164	0.2105012290545172	
+0.0050000000000000	0.0506710005765414	0.0210872495220416	9.7821058484390342	0.1662031076615633	-0.2009472687413111	0.0780993776506839	
+0.0060000000000000	0.0686853332264445	0.0062158841633205	9.8013680765814719	-0.0010742200179118	0.2461107603068574	0.2574586019315781	
+0.0070000000000000	0.0708879067166597	0.0348578829864376	9.7831212326429267	0.0836585668917330	-0.0087586479142274	0.0761276261759054	
+0.0080000000000000	0.0496117560340092	0.0044061733968517	9.8004777790692774	0.0683983155726600	0.0054433881310658	0.2326466700899424	
+0.0090000000000000	0.0484660319379780	0.0209028317217866	9.7913488334353644	0.1633593758025351	-0.0626835277985927	-0.1032091654739979	
+0.0100000000000000	0.0647041375453145	0.0231419523476783	9.7915389947200318	0.1107649313549476	0.1978153500684952	-0.0191796094830325	
+0.0110000000000000	0.0381649246936920	0.0243116772599572	9.7948916604161305	-0.0110343916575578	0.0671148366692806	0.0692856423278039	
+0.0120000000000000	0.0515576852695590	0.0204457178736043	9.8034005788368876	0.0592936491364969	-0.1481493397009060	0.0768973272084860	
+0.0130000000000000	0.0558043355551059	0.0154497772207674	9.8060239865055845	-0.0482191113358319	-0.2314733172971931	0.0249933997054341	
+0.0140000000000000	0.0586722383359979	0.0209661385100244	9.7944126604922612	0.1134950144113345	-0.2120156038959731	0.1502605216487760	
+0.0150000000000000	0.0785615275247835	0.0536925358680481	9.7708995982671816	-0.0336052316365081	-0.0155383923170866	0.0223092050669702	
+0.0160000000000000	0.0498373351166015	0.0216600377049876	9.7950800042163628	-0.0192230812393965	-0.3093945060303944	0.1386781296945100	
+0.0170000000000000	0.0653872194618586	0.0348014628968625	9.7986515400772856	0.1669719164594166	-0.2138677127743868	-0.0078135032854438	
+0.0180000000000000	0.0456215095484941	0.0122662556552829	9.7908891885985501	0.3587850721819446	0.0511424979121894	-0.0516364609549168	
+0.0190000000000000	0.0650637981860570	0.0281957714298221	9.8006601929847612	0.1616584365570262	0.0558771412540810	0.0119125686232959	
+0.0200000000000000	0.0698189659515555	0.0312077625040496	9.7963554566329432	0.0289339208170846	-0.1004028344435904	0.1538481255022801	
+0.0210000000000000	0.0574315750365525	0.0437559989221900	9.8135293463438948	-0.1927129974745410	-0.1902220082013260	-0.1330257964907460	
+0.0220000000000000	0.0618572211100974	0.0101457452618942	9.8105204198323879	-0.3047144037902024	-0.1919357622559046	-0.1377057494260233	
+0.0230000000000000	0.0682632730073153	0.0127470097166667	9.7944923977208393	0.2287621961582706	-0.0836411613674165	-0.1906916294137447	
+0.0240000000000000	0.0532942027511974	0.0243247526517187	9.8126283325899220	0.0674376357809499	-0.1031740008434597	0.0681051378287352	
+0.0250000000000000	0.0675929309906187	0.0273156532211755	9.8102866088650167	-0.0170295318844546	-0.1479776534760022	0.1938643085087097	
+0.0260000000000000	0.0830680723115975	0.0255541013202703	9.7882253041643619	0.1034246340522090	0.0715111588460670	0.0343224034793123	
+0.0270000000000000	0.0570166755170291	0.0318272845800980	9.7834019947216984	-0.0954883973063737	0.1299409566440698	0.0085770112156800	
+0.0280000000000000	0.0630221330596138	0.0076634875507456	9.7831832503345986	0.1417447861286262	0.1436002820038786	0.0430742484249294	
+0.0290000000000000	0.0746592186458344	0.0341064212044968	9.8106659295161656	0.0125425178815270	-0.1107446989824125	-0.0301242974626750	
+0.0300000000000000	0.0841574569482791	0.0367474293315586	9.7961584265085619	0.0895364320919581	-0.0013472677755115	0.2780469806868026	
+0.0310000000000000	0.0366625934695754	0.0452956417277166	9.7882217979278430	-0.0469600896066702	0.1108559429992388	0.0757212543868058	
+0.0320000000000000	0.0548348528029755	0.0364494211715692	9.8040717416034155	0.1581203743520352	0.0880569101612267	-0.0774310758358912	
+0.0330000000000000	0.0649139717260946	0.0302681467697658	9.7795446211306185	0.2141881299271403	-0.0984665194113025	0.1222793439411018	
+0.0340000000000000	0.0498733614572783	0.0316428322916459	9.7895706574635479	0.1740473527556011	0.0202119710091666	-0.0520666460668388	
+0.0350000000000000	0.0267381913612269	0.0409692407084885	9.8053850369861504	-0.4065004326784120	0.0964376257976695	0.2328786086403891	
+0.0360000000000000	0.0613248461858726	0.0200637923092403	9.7706752591476249	-0.0353481846449920	0.0537975107847130	0.4471246350958271	
+0.0370000000000000	0.0532993625431183	-0.0022234609086677	9.8024529491139276	0.3136221529849472	0.1051924380453181	0.0171267218446653	
+0.0380000000000000	0.0425457572052634	0.0134719845098001	9.8063095643077300	0.0645344288536561	0.0850072028425022	0.0219518616651199	
+0.0390000000000000	0.0596473959114695	0.0153266432963554	9.7713415625666702	-0.1396033573500143	-0.1420007686954754	0.1727724510197393	
+0.0400000000000000	0.0462842144138541	0.0116510291416480	9.8029521342599377	-0.3011521901345849	0.0334984920990516	0.2379316836460300	
+0.0410000000000000	0.0620074174566794	0.0230969982215099	9.8154367592041929	0.0616644697602823	0.0417135343853907	0.2605563084107333	
+0.0420000000000000	0.0616726875264767	0.0065336939716428	9.7946976604784677	0.1767715650188710	-0.3346367135305814	0.1863015385276423	
+0.0430000000000000	0.0468177404912740	0.0384338264350383	9.7868460621404054	0.0957611401760523	0.1593383330533058	-0.0479600241643994	
+0.0440000000000000	0.0671401822655283	0.0201704163931570	9.7782153089234320	0.4448649573000487	-0.1805273522408707	0.1852046851190660	
+0.0450000000000000	0.0589769733866553	0.0002107570499795	9.8051269236297998	0.1431527774272336	-0.2330016463133943	0.1743405860403591	
+0.0460000000000000	0.0486027656277303	0.0004531268855581	9.7912903672696867	-0.0400074749694040	0.0495043711691903	-0.0333128914877688	
+0.0470000000000000	0.0363657703032290	0.0490925244458855	9.8053412587885678	-0.1255163070917620	0.2664852084951724	0.2897907901436189	
+0.0480000000000000	0.0635238420941516	0.0287804411893011	9.8069823106379097	0.2113555363085566	0.0335792589793600	0.0773300125784461	
+0.0490000000000000	0.0687006006832048	0.0114030062147809	9.8058197516456662	0.0469210126704660	0.1558284151823030	-0.0485071236708856	
+0.0500000000000000	0.0429322623973489	0.0343097731552112	9.7835441860077346	-0.0271499912452668	-0.0481655894416542	-0.0584659477167231	
+0.0510000000000000	0.0708065608123536	0.0203939233000143	9.7991091787653914	0.1558937624653157	0.0234054228546280	0.1513521764268850	
+0.0520000000000000	0.0486137203280466	0.0475713721247955	9.8042371338950467	-0.1266579948232369	0.0333539147821154	-0.0162062101419315	
+0.0530000000000000	0.0638629145747919	0.0097576497707625	9.8126562512303099	0.2359605347539468	0.1489608729116766	0.2586891571498258	
+0.0540000000000000	0.0628700310319068	0.0166689056373651	9.7933439214796927	0.0201258251969559	-0.1810278751873291	0.0475871070964206	
+0.0550000000000000	0.0613563463160173	0.0204757457274152	9.8052920601888136	-0.0403683442543310	0.0363142253535809	-0.0320924178173908	
+0.0560000000000000	0.0757111493421350	0.0219066838792140	9.8087178727027879	-0.2508314308690538	-0.1337880411951233	0.2180544107211197	
+0.0570000000000000	0.0434394890204299	0.0218797441302505	9.7992142328585583	-0.1790297965111744	-0.0769502112883892	0.0097955671373857	
+0.0580000000000000	0.0744216843983068	0.0488466183428224	9.8032376790536802	-0.1586566119156867	0.0779575776487611	-0.1398528243939604	
+0.0590000000000000	0.0487212206670779	0.0255525847150624	9.7879369135264938	0.0617626224795987	0.1204354967851431	-0.3286326184212747	
+0.0600000000000000	0.0523274740571875	0.0339855081466321	9.7976793887560785	0.1794246980140680	-0.1602907565680522	-0.0689018955769913	
+0.0610000000000000	0.0666209347951920	0.0228812959045597	9.7876027959437852	-0.0821337651279623	-0.2677163480093408	-0.0451444894606409	
+0.0620000000000000	0.0508756154142686	0.0159389633323556	9.7930071954716507	-0.1430160942755108	-0.0439598609375025	0.1850060120918235	
+0.0630000000000000	0.0667022354721496	0.0056668845309594	9.7826035371226023	0.3724912826662609	0.1579538061904649	0.0629987410639694	
+0.0640000000000000	0.0633458117059864	-0.0129230243565272	9.8030973862769475	-0.1506787796999157	0.1907547564590342	-0.1177237805544784	
+0.0650000000000000	0.0521571439231053	0.0109618787254133	9.8165704952800521	0.1939194100640675	-0.2574551603985888	0.0201195113020875	
+0.0660000000000000	0.0591860468297405	0.0197914708417287	9.7972102497672608	0.2510110502905447	0.0326161782931683	0.1542491911685926	
+0.0670000000000000	0.0618878990697432	0.0288369120111450	9.7998978357695439	0.2131906140170175	-0.0942484996932101	0.0614531324060280	
+0.0680000000000000	0.0790780253038508	0.0418738206743854	9.7889999373805860	0.0082243369896796	0.0765679748464708	0.0394312311625701	
+0.0690000000000000	0.0584591694324888	0.0399434043625603	9.8097794282394908	0.2679654884846666	-0.0526508124637445	0.0520903088390795	
+0.0700000000000000	0.0419812488221995	0.0284661415329670	9.8089391756167839	0.0534238364054884	-0.0162600328869936	0.4579587012982511	
+0.0710000000000000	0.0597636853721592	0.0168100584896078	9.8130467580466672	0.0404392675331406	0.2633857793813721	-0.1914489398031992	
+0.0720000000000000	0.0530012352429001	0.0482902359089448	9.7922135399355916	-0.0234164650113735	-0.2758470851424254	0.1276539335560623	
+0.0730000000000000	0.0765403722475863	0.0240107705610778	9.7960911936435604	-0.0198626664105762	0.2553909314419571	0.0924500353592469	
+0.0740000000000000	0.0749437063903332	0.0335784678933192	9.7992317624287040	-0.1041771377101738	-0.0947930283968619	-0.0352747557445440	
+0.0750000000000000	0.0667470123083027	0.0326556991175517	9.8176082355467500	-0.1101189734682776	-0.2683289291376016	-0.3051600663125025	
+0.0760000000000000	0.0604020821687164	-0.0014716857317721	9.7844392309310333	0.0307197565209722	-0.0815241671440026	0.0359074959499716	
+0.0770000000000000	0.0565164108106584	0.0230650381656342	9.7858625234391781	0.0044376627632019	-0.0447230426981682	0.2839245151251671	
+0.0780000000000000	0.0559505260428720	-0.0016915523108539	9.7921109745182591	0.0616311067424773	-0.0797757911890127	-0.0039671406943917	
+0.0790000000000000	0.0569250257802676	0.0242375936650084	9.7845589927740164	-0.1166046734487762	-0.0838792124247819	0.0638822153176040	
+0.0800000000000000	0.0625541224029822	0.0056119306845203	9.8041242154801793	0.4048442838505939	-0.2357754564997804	-0.1005474973280356	
+0.0810000000000000	0.0552942532611442	0.0183098614145743	9.7956555982745996	-0.0855868747065253	-0.1016384769679105	0.3539411840757384	
+0.0820000000000000	0.0717557416430083	0.0399184353063589	9.8012104013925576	0.1679971068641781	-0.0988311279493408	0.0289625069378148	
+0.0830000000000000	0.0879030957821889	0.0064576046117466	9.7946569473203962	0.2296125852230455	-0.0630526590398515	-0.0636304058668444	
+0.0840000000000000	0.0486822264663559	0.0236951685331829	9.8091670869833258	0.0858303331055961	-0.1131243210271414	-0.0134212233211201	
+0.0850000000000000	0.0538803455773200	0.0404121347409030	9.7908399096701562	-0.1097238823549723	0.2626249296788901	0.4073918221817824	
+0.0860000000000000	0.0567224665090819	0.0305807261133096	9.8142859384009196	-0.0114220691741032	-0.2493280251363849	0.4365410942172464	
+0.0870000000000000	0.0538435215256080	0.0341438636126477	9.7760683897283602	0.3139643282701557	-0.3274407605881859	0.1353377545877495	
+0.0880000000000000	0.0402231824676645	0.0246989798415137	9.7958098021640971	-0.1259333278961908	-0.0331243849759838	-0.0126565685098989	
+0.0890000000000000	0.0545619715699633	0.0392617711040334	9.8101889664679884	0.1818693881648402	-0.0898013308803512	0.3236294447549761	
+0.0900000000000000	0.0470551509220107	0.0251767263906906	9.7915368658012643	-0.2311853155543521	-0.0470128865430926	0.1385017189572762	
+0.0910000000000000	0.0602465982349218	0.0218476067202360	9.7926639953804848	-0.0725256574177666	-0.0069573083998033	0.0989651164378136	
+0.0920000000000000	0.0512683088909017	0.0089349312420874	9.8052013715716058	0.1791246887316550	0.0486276044976046	0.1038307007219849	
+0.0930000000000000	0.0402414267666694	0.0343883482797067	9.7947054074319304	-0.2272217861444904	0.0383136310101404	0.3478789622710655	
+0.0940000000000000	0.0539203165834202	0.0284180851850779	9.8055666469356648	0.0768013927155902	-0.2892489801244795	0.3567874117091382	
+0.0950000000000000	0.0464967286646541	0.0123211969518301	9.8008672114886330	-0.1301844919038110	0.1371465403334597	0.0672405337535900	
+0.0960000000000000	0.0803743919320035	0.0383579474844168	9.7973691852320464	-0.0806779895603294	-0.2109349138666940	0.0056846287599455	
+0.0970000000000000	0.0558827805194775	0.0216632267732484	9.8081423322037296	0.2234771905731263	0.0745059463508716	0.3350300983790765	
+0.0980000000000000	0.0684715544689999	0.0074998022958611	9.7866847321297907	0.2463838461049139	-0.1970603541513191	0.0952099270932230	
+0.0990000000000000	0.0455663294829773	0.0178767700601485	9.7896662709098639	-0.1207514291336319	-0.1180051373905544	-0.0835202667633991	
+0.1000000000000000	0.0717301163322155	0.0035946147974133	9.7928386080822065	0.2739254443250081	-0.0818067005060924	0.0375113428791556	
+0.1010000000000000	0.0545517496863676	0.0075022169419739	9.8029232141890024	-0.0036825690712586	0.0273842948457056	-0.0378912395876205	
+0.1020000000000000	0.0300557115044005	0.0269393776347306	9.7951770012593613	0.2467513576081480	0.0714485349749600	0.1157529442680685	
+0.1030000000000000	0.0691495248047884	0.0266599070047928	9.7581043772947673	-0.0413182017560696	-0.3642833049518236	0.1497657042968721	
+0.1040000000000000	0.0461009126426735	0.0117702928884190	9.8067750628797370	0.1066414161610422	0.1534961857599433	0.1298954623873088	
+0.1050000000000000	0.0806160399470138	0.0368803881486176	9.8039487585819955	0.1749040900483307	0.2463783483729851	0.1279554004989031	
+0.1060000000000000	0.0541272175549846	0.0201908235026090	9.7983730256576873	0.3664280589095602	0.1065309048585471	0.1031971868826981	
+0.1070000000000000	0.0626673466933850	0.0216134660717341	9.7990055059333958	0.0291843583847081	0.1621736547716670	-0.0604203360601649	
+0.1080000000000000	0.0713241340386279	0.0542009202057757	9.7967336341860900	0.0718171743819865	-0.0310540818574127	-0.1418917354516139	
+0.1090000000000000	0.0927858010139449	0.0277226025434756	9.8128790840555133	-0.0730269256293523	0.1175286449820847	-0.1487370092683145	
+0.1100000000000000	0.0493643928713543	-0.0045859096414039	9.8075057003311041	-0.0248840968575224	0.2870246136459492	0.0379805965217619	
+0.1110000000000000	0.0583863926728930	0.0423172711415685	9.8016973815645088	0.1232649836197240	-0.1036772104881333	0.0809565225851609	
+0.1120000000000000	0.0542666125173206	0.0154829348862819	9.7902695915808078	0.0169402925466260	-0.1300019914360065	0.1159582885642121	
+0.1130000000000000	0.0581492399359025	0.0329289536115948	9.7890538705667325	0.1300033524012513	0.2704221197071184	0.3730546484025617	
+0.1140000000000000	0.0744324665978534	0.0438236182558423	9.8046372571983955	0.0157239505927532	-0.3845111816325550	0.2473789858793749	
+0.1150000000000000	0.0815643103170347	0.0270023358758213	9.7920338726716079	0.1656287850477982	0.0645062933575507	0.0072877133485550	
+0.1160000000000000	0.0822291206372497	0.0247326889937187	9.7891904851863742	0.0019615640478332	-0.0231065860856135	0.0537141238753317	
+0.1170000000000000	0.0733878213160416	0.0405135529035182	9.8224230479788961	0.0857912780445161	-0.1337481599158919	0.0916368130640879	
+0.1180000000000000	0.0746262839357992	0.0314733772289359	9.7922091128238549	-0.0207820450392441	0.0582122670824746	0.0138357205323391	
+0.1190000000000000	0.0659522684275811	0.0310802255454785	9.8079830812276452	-0.1463659778594223	0.1561056239102843	0.0583635588633533	
+0.1200000000000000	0.0773762983660368	0.0286306663964581	9.7843648898107141	-0.0320619293134633	0.1401296984351160	0.1803134875807527	
+0.1210000000000000	0.0397274215806393	0.0091072064711053	9.8303629821962968	0.0522813356288703	0.1252626142168111	-0.0913425549637287	
+0.1220000000000000	0.0859906103223147	0.0115916460396800	9.8015070830034112	0.2223253479611627	0.1231700896169124	0.1151223630297517	
+0.1230000000000000	0.0604257390416243	0.0273872188432711	9.7960529760033914	-0.0562134807025564	-0.1522832504289026	-0.0980519386783659	
+0.1240000000000000	0.0752386091976694	0.0330615921110760	9.7981528615687985	0.3957622942841056	-0.1403697049785635	0.0039212324473493	
+0.1250000000000000	0.0518321741258240	0.0121221010499456	9.7793421257644173	0.0961776623228478	-0.0564661539625346	0.0756374802075537	
+0.1260000000000000	0.0609080367393529	0.0237269553175497	9.7933295456190859	0.0202386226180327	-0.1430638766189263	0.2416205866240601	
+0.1270000000000000	0.0565374133574573	0.0211361054190409	9.8122533422791953	0.1107382834631654	-0.1060003069433449	0.2211154615379658	
+0.1280000000000000	0.0469081954829633	0.0340103057703895	9.8017835339159749	-0.0820880762452793	0.1290738496722628	-0.1846634522215389	
+0.1290000000000000	0.0785213023094349	0.0381409921932119	9.7904423604741986	0.0099722684093057	0.0165458677125349	0.0384873569652332	
+0.1300000000000000	0.0608369609807276	0.0173041858334243	9.7986910608548907	-0.0725919736327255	0.1346735414450026	0.0475302158907624	
+0.1310000000000000	0.0776483833855985	-0.0101889111736586	9.8155978727701569	-0.0463658272952836	-0.1740812983196158	0.1965227601491907	
+0.1320000000000000	0.0609149455482128	0.0559700057729310	9.8024994458887260	-0.0454275076957628	-0.2115075454820566	0.1636179777723830	
+0.1330000000000000	0.0534516287458471	0.0157355945632138	9.8026735958973354	-0.2027405643725755	-0.1213394881186760	0.0052789450128654	
+0.1340000000000000	0.0653247868499723	0.0354702211700883	9.7990179852754444	-0.2485005510007451	0.0124511844592918	0.4120169433060356	
+0.1350000000000000	0.0705709852372540	0.0092413577732448	9.7890671048933147	0.2280794753129544	0.0929401393254017	0.1424492298540375	
+0.1360000000000000	0.0497473343512680	0.0240965433279384	9.7744052423573731	-0.0271445385789343	-0.0442609417211934	0.0319367694346342	
+0.1370000000000000	0.0668893146214413	0.0213149614231242	9.7886361444883274	0.2867776221900452	0.0293274175757716	0.2357442012443713	
+0.1380000000000000	0.0694064562222662	0.0391409500982695	9.7984549580966522	0.0014914437637582	0.0677308507892862	0.2178504582107250	
+0.1390000000000000	0.0656832546226440	0.0084972734504968	9.7944046583284656	-0.1907658295434309	-0.0085260580239538	0.0432867249912242	
+0.1400000000000000	0.0792690057000107	0.0427287669913801	9.7939017800917227	-0.0918137634887668	0.0500996544663029	0.0923523057994816	
+0.1410000000000000	0.0529971144836228	0.0180807232748345	9.7900970435545869	-0.0821282399002137	-0.0275068344980564	-0.1195674020131415	
+0.1420000000000000	0.0583024034455197	0.0266232358163522	9.8285756411177925	0.0067601332298214	-0.0769879037346868	0.0759510166170168	
+0.1430000000000000	0.0476640469028924	0.0334673398716236	9.7946951965599443	0.3344377022430290	0.0769732033796138	0.0839400207086585	
+0.1440000000000000	0.0598563509297998	0.0367272389242608	9.7797759278296983	0.1423492599329000	-0.2044430375488129	-0.0816359570720174	
+0.1450000000000000	0.0746815889423625	0.0250003976998319	9.7923257880083199	0.0718249860730075	-0.0211294881374947	-0.0931591014631945	
+0.1460000000000000	0.0763380422511314	0.0243878730861223	9.7828733005886654	0.0690527480073031	0.1176227346830175	0.1962403260449566	
+0.1470000000000000	0.0468060743216666	0.0145318258061914	9.7964729726481004	0.1912637909380544	0.1017137567665658	0.0467560771628032	
+0.1480000000000000	0.0558013184920857	0.0199307631540313	9.7883553162012884	-0.0333437471756057	0.1496603944222712	0.0834541276989452	
+0.1490000000000000	0.0692461358805761	0.0285115571025213	9.7770622423629820	0.1127336544981873	0.0290132589060476	-0.0460631444366676	
+0.1500000000000000	0.0622375543089070	0.0342662186935736	9.7954448846286724	0.2841287776613627	-0.1184460773644618	-0.0708829813825268	
+0.1510000000000000	0.0518050002502732	0.0070911619150990	9.7979583895695335	-0.1701220560122760	-0.0713173190278044	0.1193854185033465	
+0.1520000000000000	0.0593502289830920	0.0084167154956298	9.7744280089970630	-0.1445149668310071	-0.0426680666624523	-0.1243799333436834	
+0.1530000000000000	0.0509769596085691	0.0105107841198091	9.8013331072350258	0.0788062488721322	-0.0827599594378275	0.2250666509929658	
+0.1540000000000000	0.0513382094759807	0.0281262016045423	9.7850917695051791	0.2885362645015004	0.0187120521155820	-0.0659945834772924	
+0.1550000000000000	0.0711620358903478	0.0109050549785608	9.8028591905385927	0.0561973840251722	-0.0605097355275710	-0.0169580050531356	
+0.1560000000000000	0.0621742958020185	0.0358331107555402	9.7987343356693710	0.2351824644115450	-0.0025910161700164	0.0807744334518068	
+0.1570000000000000	0.0579000624080185	0.0246952686106224	9.8004626135634947	0.2220006321864781	-0.0356149548199383	0.0856675616766092	
+0.1580000000000000	0.0703304313837786	0.0178002692445028	9.7778143975586858	0.1070428099229889	-0.0940157184242589	0.0783641470999581	
+0.1590000000000000	0.0611426601743330	0.0409739616284168	9.8041204959409551	0.1399532362490387	0.1470743046915458	-0.0800941219485791	
+0.1600000000000000	0.0620734103022896	0.0346130544318330	9.7979927837588061	0.0467456782513449	0.0868000289708127	0.3389114646919866	
+0.1610000000000000	0.0498188104187756	0.0399760309080708	9.7856350289207246	0.1420633607873164	0.3077254929348689	0.3413488183925373	
+0.1620000000000000	0.0659802370691349	0.0354879980777699	9.7856363301605072	-0.0234892916953389	0.1012713172238394	-0.0126591302779482	
+0.1630000000000000	0.0616087001507330	0.0654493057538344	9.7970887495582630	0.0107810790796595	-0.1504139168164459	0.1741102041349321	
+0.1640000000000000	0.0501913057427650	0.0417568456101255	9.7972389540143237	0.1209357500699452	0.0189137531063997	0.1101938618196022	
+0.1650000000000000	0.0684562412616551	0.0247221215263129	9.8123203062856934	0.0356150607651081	-0.1085940892328260	-0.1008496314500209	
+0.1660000000000000	0.0624721055437283	0.0337032863754500	9.7808714083211168	-0.0775188723883550	-0.0454856607861791	-0.2491391704592327	
+0.1670000000000000	0.0574178290883711	0.0263406272304249	9.7885827990734846	-0.1012586164783007	-0.1705410533376906	0.0358251707382042	
+0.1680000000000000	0.0626521308720349	0.0186245176490059	9.8015622112930263	0.1856743596325400	-0.2332851026175928	0.0908946332526481	
+0.1690000000000000	0.0330024856266654	0.0262838284324073	9.7976729489377767	0.0256904940055174	-0.1951660144011184	-0.1265367411914239	
+0.1700000000000000	0.0709483523893598	0.0272907161981631	9.7929291394778275	-0.2944771270943435	0.3126394476837783	0.1925933528544082	
+0.1710000000000000	0.0589474540125117	0.0341658450871620	9.7949425233275385	0.4358596595323214	-0.3094592385862462	0.3579922685912313	
+0.1720000000000000	0.0388322181607915	0.0416915694491585	9.7864690408368329	0.4590926139017208	-0.0625929878815203	0.1272943097726741	
+0.1730000000000000	0.0577620481703183	0.0017638687488277	9.7913431069659538	0.0288094282630140	-0.0700130353760138	0.1676437592267120	
+0.1740000000000000	0.0348691845157323	0.0175655368068565	9.7976014102680899	0.1656279778792275	-0.2468442053039965	-0.0181681296669870	
+0.1750000000000000	0.0782618143150379	0.0153593182999095	9.8004490688869232	-0.1025636294395587	-0.0174435453817711	0.0003982277106851	
+0.1760000000000000	0.0831084943135663	0.0417460074041505	9.7816069904094292	0.2604207562728299	-0.0283961199434715	-0.1605105027517282	
+0.1770000000000000	0.0550621906141784	0.0310978980508068	9.8030082959591756	0.1103936465759237	0.1296343611333921	0.2556827900530585	
+0.1780000000000000	0.0729505743154777	0.0344556352779658	9.7942688780913354	0.0838246553608946	0.0229278330740620	0.1497298632680755	
+0.1790000000000000	0.0711724201555954	0.0370885734678371	9.7973871938151653	-0.1077326277444671	0.2845035530115818	0.2142541833664772	
+0.1800000000000000	0.0810069778365470	0.0225747777496008	9.7978314847342247	0.0524817146929127	-0.3027777639110976	-0.1919372449858948	
+0.1810000000000000	0.0426261401063904	0.0354795772553315	9.7927126835921889	0.0965670512941401	0.0329733658258361	0.2006741748034878	
+0.1820000000000000	0.0514706381051834	0.0309004222598948	9.7868206658509127	0.0857643663745337	-0.0604463131516309	0.1602590302416712	
+0.1830000000000000	0.0493105203337564	0.0133535658093260	9.7898518392586737	-0.0679410500515818	0.0757731094969861	0.1222624910411960	
+0.1840000000000000	0.0604703299538459	0.0291178002162318	9.7930026150455376	-0.0440431310410827	-0.1217638804025265	0.3722940534699428	
+0.1850000000000000	0.0928460518906970	0.0259557894180615	9.7852752473176370	0.0967353276763562	-0.0483500200679131	0.1262695311007123	
+0.1860000000000000	0.0573168247710957	0.0402522902523168	9.7948167590222646	0.0047213627886438	0.0245880842063973	0.2692379560465731	
+0.1870000000000000	0.0447285825684236	0.0374737189297723	9.7843837069566941	-0.0868478504093683	0.0816433355806336	0.1120360957464380	
+0.1880000000000000	0.0555324435484944	0.0372681873793480	9.7708955471389487	0.0629146852532116	0.0357401907247330	0.1209622490771063	
+0.1890000000000000	0.0367565531336745	0.0288139090939491	9.8031254832536838	-0.0625610747458778	-0.2931464414810676	0.2550143505081076	
+0.1900000000000000	0.0548604392269366	0.0232052679017736	9.8010633002563807	0.1725750668610432	-0.2128696261642450	-0.1705866615624085	
+0.1910000000000000	0.0460875756634826	0.0208522963800843	9.7887430583146369	0.2464570934466301	-0.2790831107272194	0.1196652456905332	
+0.1920000000000000	0.0678514320371909	0.0230971520449340	9.7816391783699181	0.0214266602100786	0.0967647119967464	0.0687722176170424	
+0.1930000000000000	0.0657320543405707	0.0289965499779984	9.8095007114029542	0.1204702153154908	-0.1249688367640578	0.0585191124224156	
+0.1940000000000000	0.0658421654723391	0.0247097369002959	9.7878675517710754	-0.1491575098075792	-0.1136524752280824	-0.1171895085318980	
+0.1950000000000000	0.0957559497021957	0.0273528058773340	9.7926079920561655	0.1652421364836570	-0.0864137737975956	0.0911223059596503	
+0.1960000000000000	0.0820935084545803	0.0195613642635530	9.7810471769059326	0.1468512431569419	-0.0761746147207100	-0.0791964213305181	
+0.1970000000000000	0.0676173523116083	0.0303884027874410	9.7814706439486656	0.3153906519254008	-0.0465027016019540	0.2389815115901093	
+0.1980000000000000	0.0901842468498708	0.0156497582048447	9.7918082273740463	0.2295193114175836	-0.1267401432553094	0.1549662996266503	
+0.1990000000000000	0.0516274391501831	0.0422516837263391	9.7907523540072958	-0.0330008727138860	-0.0218550656974865	0.2913087900256289	
+0.2000000000000000	0.0504916635778898	0.0172787805764225	9.8039921305132598	0.2700850660585061	0.2532802499070314	0.3083109038591090	
+0.2010000000000000	0.0461662985756255	0.0296552063010067	9.8199234514643301	0.2702834559177846	0.1787880045189220	0.0309306849350942	
+0.2020000000000000	0.0811601445279619	0.0451160681107020	9.8039036608667338	0.2353056576570380	-0.0850242215461672	-0.0636894842244430	
+0.2030000000000000	0.0419149693804611	0.0181353941896105	9.8027162199939006	-0.1608600970615389	0.0893860839541451	0.0476046907213388	
+0.2040000000000000	0.0758066399172299	0.0225497196301978	9.8022893421677981	-0.0761719790132482	0.2635903426877931	-0.0076585239731397	
+0.2050000000000000	0.0603196099882879	0.0372038706007467	9.8139569224039658	-0.1164651293346436	-0.1439005513601156	0.2432151102870336	
+0.2060000000000000	0.0627313775993070	-0.0004049577713357	9.7752032532762172	-0.1557647577383244	0.1042444243157966	-0.0676806129405985	
+0.2070000000000000	0.0594849488311693	0.0479601446421634	9.8107609785804328	-0.0290304033125488	-0.0516530693699868	0.2431633288577618	
+0.2080000000000000	0.0794307542556529	0.0264580305679772	9.8026423069394415	0.0187690726431836	0.0168678661521759	0.1911287537921306	
+0.2090000000000000	0.0614179222813421	0.0424579337169686	9.7908485445665736	0.1615930204649895	0.0680471627470343	0.0924779680940519	
+0.2100000000000000	0.0806084761564366	0.0136639198619717	9.7990970711873793	0.0564283301595925	-0.2197713164512612	-0.0464122100552717	
+0.2110000000000000	0.0588927247619423	0.0327069600447449	9.7993519542601106	0.1146546073042721	0.0356240456544198	-0.0351309025425864	
+0.2120000000000000	0.0770547476898458	0.0135961389180790	9.8124078224893641	0.0416594709717551	-0.1218920191687169	0.1816350635440960	
+0.2130000000000000	0.0581618353217321	0.0112473747982415	9.7786799515230527	-0.1429510381248832	0.0538903545149791	-0.0735724215870114	
+0.2140000000000000	0.0605350329898321	0.0494347652229342	9.8046485418162277	0.0691152901768394	0.1610116180949691	-0.0412717437104294	
+0.2150000000000000	0.0627241371860912	0.0130028122344430	9.7814095197556110	-0.2161069083716002	0.0549556905617030	-0.2253703608554513	
+0.2160000000000000	0.0536617028601043	0.0245307357995530	9.8037035861528476	-0.2765691984568266	0.0175919226564776	0.0932802252032465	
+0.2170000000000000	0.0615106454366726	0.0108980318940529	9.7974470568176351	-0.0866184086846734	0.0322681762019665	0.2139234880020909	
+0.2180000000000000	0.0668838748254429	0.0231988896107143	9.7863501831094961	-0.1681682357831689	-0.1270041036038325	0.0723497131521894	
+0.2190000000000000	0.0569707771744100	0.0281590449261759	9.7853792385989262	-0.1029923383553604	0.3157782580132116	0.0061332046072239	
+0.2200000000000000	0.0481651933175016	0.0360565679570361	9.7731458302737817	-0.1219583222216318	-0.1163303419276196	0.2864706091137976	
+0.2210000000000000	0.0837508111161770	0.0101635273015035	9.8028205839813580	-0.0783650503615651	-0.1861282733167385	0.1914189360687693	
+0.2220000000000000	0.0522799851281602	0.0342139589701018	9.7903440597304865	-0.2460670662502277	-0.0003830968241798	-0.1068971702938922	
+0.2230000000000000	0.0751065833416516	0.0246249494232841	9.8183361258883330	0.3054207477612957	0.1991230850710527	0.0274049357851692	
+0.2240000000000000	0.0851611461505393	0.0393572060333921	9.7694641348910984	0.0412187516784849	0.1521083139793882	0.0272560106736247	
+0.2250000000000000	0.0482158228586572	0.0397768085660382	9.7986907164283163	0.0651884191099909	0.0184045139691787	0.0172421866586214	
+0.2260000000000000	0.0622358812746295	0.0179170184506069	9.8023743331607331	-0.0786632793093210	0.3658482240399782	0.1597474302039841	
+0.2270000000000000	0.0460388900587514	0.0196085629116743	9.7774564749221895	0.0282870374698370	-0.1612866429147711	0.2820809745342175	
+0.2280000000000000	0.0393773304925111	0.0075201349106894	9.7816482943622649	0.1222888299908510	0.2244820973961600	0.0684503874356055	
+0.2290000000000000	0.0518529767643139	0.0374667269451129	9.8157170943064571	-0.1886049930131664	-0.0891608004035405	0.2983745120230226	
+0.2300000000000000	0.0611046211664386	0.0293378424990877	9.7872999989115339	0.0844835315224069	0.0802847513847847	0.2029042508837181	
+0.2310000000000000	0.0674125489175328	0.0283422663013969	9.7983615766828205	-0.1734377172816484	0.1792370474902763	0.2799715268306627	
+0.2320000000000000	0.0525614261748299	0.0279626269945506	9.7999366779620516	-0.0991567115031925	-0.0274744992070562	0.5759818831283097	
+0.2330000000000000	0.0600484178581328	0.0132667437558142	9.8109669994294855	0.0144709695628432	0.0710838691824587	0.1516916316181474	
+0.2340000000000000	0.0779650151786236	-0.0000791219644342	9.7799512447357912	0.0618774580113176	-0.0814701293073927	0.1547545052817120	
+0.2350000000000000	0.0709120122494550	0.0290028092905407	9.7810607622544321	-0.0814482032309889	-0.0681337223582168	0.0305980431733347	
+0.2360000000000000	0.0706224976789882	0.0220740791794032	9.8007936648772436	0.1326634638041140	0.1085947344525075	-0.0376414713747330	
+0.2370000000000000	0.0547848558233412	0.0207333697959867	9.8073562168855251	0.0102820781282158	0.1141692437653569	0.0407699435239955	
+0.2380000000000000	0.0585395755827252	0.0129447235838562	9.7944585124602188	-0.0551274962024374	0.0084550840731188	0.1394858109481595	
+0.2390000000000000	0.0572645654752040	0.0128404028429086	9.8103846799748400	0.1587634283107595	-0.0300506784419461	0.0129809732326113	
+0.2400000000000000	0.0546663051206739	0.0350211170731095	9.8041411056205963	0.2557163414272539	-0.0667827166135776	-0.0054636147641773	
+0.2410000000000000	0.0532669603371623	0.0346363038028856	9.7967404735281551	0.2267229858285966	0.1349362222234306	-0.1384866330408252	
+0.2420000000000000	0.0574384049856053	0.0096950692033144	9.8036729767236324	-0.1384150265072777	0.0759870167851818	0.3027772702422811	
+0.2430000000000000	0.0668094977400519	0.0321122030478266	9.8067137398734694	0.0762004628178817	0.0138981123702045	0.0441015230637358	
+0.2440000000000000	0.0832850774880092	0.0072916747247701	9.8165805946812839	0.2331141320175399	0.1289389875758163	-0.0141343352118625	
+0.2450000000000000	0.0618947566841425	0.0308060500298105	9.7996051505826252	-0.3954318301445775	-0.0827485289864532	-0.0550382698700718	
+0.2460000000000000	0.0514593477857901	0.0127685847300933	9.8091932537292728	0.1341412529039472	-0.0197290404357718	0.0862446225161482	
+0.2470000000000000	0.0633226960142771	0.0252034579413736	9.7944899932475735	-0.1297534049492307	-0.2239947811199794	-0.0568955357750971	
+0.2480000000000000	0.0630792907797783	0.0280750692605070	9.7922471037128318	0.1049172555340925	0.1126397344034828	-0.0993169874639670	
+0.2490000000000000	0.0652954794825730	0.0400579860395722	9.8145188147341074	0.2508079949095635	0.0075318440952331	0.2711743929528881	
+0.2500000000000000	0.0568741293797479	0.0333406419294481	9.8093998233780475	-0.0935224143157517	-0.0999372024209757	0.1250986214430684	
+0.2510000000000000	0.0311941469744073	0.0212174154425351	9.8057767580887756	0.0583812915057094	0.0872381999145534	0.1416454875160951	
+0.2520000000000000	0.0611845755517848	0.0341046479966752	9.7886604975372808	-0.2196468863751269	-0.0998618596965940	0.1162744777470494	
+0.2530000000000000	0.0538380041115368	0.0386664072779871	9.7757458497850678	-0.1548489119681329	-0.1670806941469321	-0.0147370964388921	
+0.2540000000000000	0.0452340235001366	0.0194314300196694	9.7646994764844237	0.1383983659208224	-0.2012142766118825	0.2810686085173245	
+0.2550000000000000	0.0679861354409167	0.0148630713681617	9.7998235416018531	0.2608646940784916	-0.1288817714064481	0.1994590909315425	
+0.2560000000000000	0.0792664058451464	0.0078171959379993	9.7892259953416207	-0.0617254247661862	0.0334663327666473	-0.1533925110159549	
+0.2570000000000000	0.0601958431058459	0.0170515468498050	9.7895463392684725	-0.1318772523043783	0.1384150156212377	0.0664886218702340	
+0.2580000000000000	0.0546722262516031	0.0219604210410744	9.8107372412920633	0.3108820453028625	-0.1026528328738082	0.1940010165217763	
+0.2590000000000000	0.0699230904855573	0.0262025036945064	9.8070734928727958	0.2242440644433699	0.0440437291076402	0.0386636957159784	
+0.2600000000000000	0.0574545918268981	0.0118842682424116	9.8098673365626841	0.0074571628413052	0.1903270958835050	0.2511262362215447	
+0.2610000000000000	0.0579828586290340	0.0066633382520305	9.7986068575920910	0.0521155251413847	0.1910339588030088	-0.0333881363609672	
+0.2620000000000000	0.0709902207021370	0.0335594609716364	9.8058107962598857	-0.0545721686036513	-0.1714984065867731	0.1942616145060788	
+0.2630000000000000	0.0597248414458850	0.0255314877176391	9.8082186791911710	0.1790262577659056	0.2349360500999531	0.0347161034951954	
+0.2640000000000000	0.0661364684886499	0.0350349588691763	9.7914277958920835	-0.0234980619677222	-0.0467940223139066	-0.0433905361830537	
+0.2650000000000000	0.0606810035208515	0.0090638295873126	9.7903239781219700	0.0728158049663853	-0.1014997673650121	0.1580903075082015	
+0.2660000000000000	0.0511846587722291	0.0245044117289052	9.7999253673804176	0.0608699833442126	-0.0469544789828718	-0.0925267864134375	
+0.2670000000000000	0.0518204382908487	0.0203116997526307	9.7913305141193074	0.2609441871299780	-0.0233926267123880	-0.0013890344920213	
+0.2680000000000000	0.0533358657157283	0.0118985126838566	9.7979150074355204	0.1689490892533402	-0.1044925925384208	-0.1338475039475009	
+0.2690000000000000	0.0631683098393498	0.0158706618207159	9.8017529551491549	-0.0291122306055468	0.1348035916343066	0.0503219047857159	
+0.2700000000000000	0.0676799834893126	0.0527904361243941	9.7928031983273449	0.2536000305077145	-0.0215317515643491	0.2187626345050843	
+0.2710000000000000	0.0688925424037692	0.0231024394992590	9.7988780180642063	0.1789435549825043	0.0032937236243494	0.1626562118478387	
+0.2720000000000000	0.0476324482327280	0.0238153931049186	9.7765174538932982	-0.0658671164600632	0.0877777342378192	0.0471763332103760	
+0.2730000000000000	0.0631707679458461	0.0230900300179133	9.8120409826710695	0.2068357218654407	0.0943688185437535	0.1369723572391947	
+0.2740000000000000	0.0507029774806738	0.0469870109260102	9.8088855389595402	0.2019883421655503	-0.0406652585313225	0.0737253089024909	
+0.2750000000000000	0.0536439944559708	0.0135798900046714	9.8014803221431670	-0.0018138328468976	0.0157378838609933	0.0854881890686849	
+0.2760000000000000	0.0459216983982091	0.0241959971777195	9.8039042224104520	-0.0832637555806814	-0.3072324951948956	0.0542410343351695	
+0.2770000000000000	0.0456847961500159	0.0123293435425375	9.7734565693158260	-0.0875985055932773	-0.0817619339145602	-0.1096491084690106	
+0.2780000000000000	0.0486047499057723	0.0191091152033784	9.8032098963014196	-0.0160776802086463	-0.0464120622202341	0.1822343905738396	
+0.2790000000000000	0.0547812967819831	0.0245733206670207	9.7858454185104709	0.0114293985665191	-0.1031702082171306	-0.0654309297590266	
+0.2800000000000000	0.0690025092361258	0.0334773341914145	9.8006390982229039	0.1986349797208066	-0.1151114448584877	-0.0296538295688934	
+0.2810000000000000	0.0615026679644718	0.0166833452862676	9.8062687929187380	0.0145105289917296	0.0379846927616131	0.1956793719333565	
+0.2820000000000000	0.0420065404445642	0.0340609110873616	9.7960787932184221	-0.0475897951402455	0.1610906215652200	0.0924425376013092	
+0.2830000000000000	0.0573435899536079	0.0278582103363420	9.8063594248446417	0.1145161175240017	-0.1213466773455496	0.1859953011908591	
+0.2840000000000000	0.0763293201123695	0.0239343882393496	9.7848921575046575	-0.3674294296833675	-0.0812251054168599	0.0077901915722137	
+0.2850000000000000	0.0490703579731148	0.0485400947383012	9.7808778198941138	-0.1956565248254560	-0.1157301916376558	0.0792154154501079	
+0.2860000000000000	0.0510604049794761	0.0280472918397093	9.8026891712963700	0.0574865825293452	0.2128431095722229	0.0642566118131865	
+0.2870000000000000	0.0650471840472040	0.0434474983273593	9.7821787274338750	0.0706879224766745	-0.0609288420580826	0.1236314486556981	
+0.2880000000000000	0.0825354754561708	0.0560611384936597	9.7855146746295603	0.1015013310966248	0.0616868819519499	-0.0333345208611952	
+0.2890000000000000	0.0617001105994277	0.0408094168081509	9.8013845138712110	0.0606054213577117	0.0586644765525347	0.1473206874181207	
+0.2900000000000000	0.0707744150698713	0.0308084031813292	9.8104166649244640	0.3095404650524101	0.0689982840948250	0.0339698968491600	
+0.2910000000000000	0.0552216281998847	0.0232685261418999	9.7953161845541707	0.1210219319488115	-0.1044730117659549	0.0495112892347083	
+0.2920000000000000	0.0660070946964242	0.0028075374169110	9.7983736188857247	0.1240850317635916	-0.0262512090285870	0.1494146216791622	
+0.2930000000000000	0.0527339884538274	0.0159873656768855	9.8047338919918356	-0.0401007684859817	0.0032926139003812	0.0803596489289140	
+0.2940000000000000	0.0424013652750079	0.0347804238692492	9.7935272543167198	0.0488017405993763	0.0922978552862160	0.0919907045524636	
+0.2950000000000000	0.0339577451503068	0.0372363542737731	9.7906961270548134	0.0498199628813751	-0.3172633376668123	0.2571776649924757	
+0.2960000000000000	0.0677412559776200	0.0408439880500846	9.7787770610147220	0.0603675079822698	0.0185883281405876	-0.2176748288954304	
+0.2970000000000000	0.0559100251631861	0.0415038187873226	9.8107715715666668	-0.1599640908445767	0.0390656273256561	0.1143451382389790	
+0.2980000000000000	0.0559012384178881	0.0105421242248316	9.7964691859506736	-0.0412112813989374	-0.1504807741985786	-0.0603596295177136	
+0.2990000000000000	0.0586843296729206	0.0323343026686275	9.7999384337474389	0.0577969083968577	0.0043412717912011	0.0078745617093137	
+0.3000000000000000	0.0549021056643711	0.0178915425813221	9.7690463674698638	-0.0071878838657406	0.0797390680090613	-0.0503163420626112	
+0.3010000000000000	0.0777036424716496	0.0147768024399995	9.7983129155017945	0.0432701237466338	-0.1126663242060236	0.1137017868195785	
+0.3020000000000000	0.0715549567306365	0.0145520939901289	9.7917158796414316	-0.3357283897353760	-0.1613819726374447	0.0980499916331792	
+0.3030000000000000	0.0829018337564642	0.0252822495479954	9.7916304875093534	-0.0222148073159008	-0.0116138686075747	-0.3180453894612836	
+0.3040000000000000	0.0551806613119749	0.0184264031674693	9.8036975377532869	-0.1553677312055443	0.0215351149344567	0.2747632401089575	
+0.3050000000000000	0.0791634873355407	0.0277444869544260	9.7953673377361135	-0.2977412121000060	0.0189524397721860	0.0220963629103427	
+0.3060000000000000	0.0559381664481210	0.0180090393978018	9.7897996305843353	-0.0188517852908278	0.2422190420832186	-0.0789082554631691	
+0.3070000000000000	0.0649792220781952	0.0148027429140541	9.8058774797132653	0.0796848792414155	0.0794708697532488	0.1061768469126607	
+0.3080000000000000	0.0603488749083254	0.0150001265350089	9.8095005612481874	-0.1808075645659544	0.0753083987269400	0.2120697987926287	
+0.3090000000000000	0.0428694906476075	0.0393595159916285	9.7928560309208095	-0.2230232749311995	-0.0945467358646019	0.2851944229748622	
+0.3100000000000000	0.0696794079793379	0.0330544089594562	9.7946914010489046	0.1091708951968354	0.1774616286941363	-0.0181593350280776	
+0.3110000000000000	0.0567586375962516	0.0358273903542780	9.8053384747898029	0.0206401442777312	-0.2041754545335933	0.1771253103988810	
+0.3120000000000000	0.0589445712371951	0.0047493809186219	9.8273397627708601	-0.1627162235502447	-0.3292717934516943	0.0489757404590287	
+0.3130000000000000	0.0535147872378386	0.0304838234475489	9.8204341029034481	0.0355831243691146	0.2018119749602222	-0.0530000281160418	
+0.3140000000000000	0.0693557099689130	0.0328089439220941	9.8019328096959715	-0.0965032219939279	-0.0172557695298318	0.0697591651985237	
+0.3150000000000000	0.0717827507431828	0.0133619571192957	9.8002043958971825	0.0130210298436067	-0.0912616038440353	-0.2715839833813453	
+0.3160000000000000	0.0500173286507072	0.0153422464363002	9.8206809985551970	0.0042471585969678	0.0357216151949515	0.1824409740557745	
+0.3170000000000000	0.0589365257769131	0.0106780216444542	9.7988642230693781	0.2636718523703891	0.1335266382987390	-0.0016008058029399	
+0.3180000000000000	0.0625376878449450	0.0245350147536060	9.8002798791486718	-0.1102199103895965	0.1358332032958192	0.2758791215995601	
+0.3190000000000000	0.0713980398326928	0.0321055607096478	9.8040879646391055	0.0283225307020613	-0.2089028025535080	0.0069623175869483	
+0.3200000000000000	0.0660968121480837	0.0117810595541276	9.8153222210896551	0.2572843055311435	-0.0868730851000479	-0.0901232490392259	
+0.3210000000000000	0.0687026955746080	0.0304418861869680	9.8042545278916950	0.1526101566073427	0.0796767327330062	0.1041778661037888	
+0.3220000000000000	0.0771729732428774	0.0293341993019450	9.8055940537640520	0.0236142800580601	-0.1334049654274596	0.0251810830531954	
+0.3230000000000000	0.0732135260941903	0.0176556203107591	9.7768074582913442	0.3078831080939231	-0.2385918261122460	0.3856406786830869	
+0.3240000000000000	0.0486184616300351	0.0422680271321205	9.7926317737089370	0.0013775536573449	0.3026451498269482	0.0243150787122249	
+0.3250000000000000	0.0737589355449495	0.0189524769985781	9.7968164742356123	0.0056457552569826	0.0853917540123950	0.0308348202037366	
+0.3260000000000000	0.0502265475026565	0.0330499581644075	9.7957863439127966	-0.3390572053436181	0.1901273879977756	0.0839291684737039	
+0.3270000000000000	0.0715588589604746	0.0305038446088477	9.8126189419325875	0.1364915546254858	-0.1401563582821170	0.1262338758598522	
+0.3280000000000000	0.0510442147322608	0.0010164805212456	9.7840943685580619	-0.0202351928518969	0.0239725819337122	0.3401201259824597	
+0.3290000000000000	0.0573217680915375	0.0379399536394980	9.8200417963571347	-0.0596098886062081	0.0661578126376448	0.2698240858844160	
+0.3300000000000000	0.0703633577661224	0.0297145401574222	9.8116138524161869	0.2905700902512395	0.3606233838319439	0.0621611138533324	
+0.3310000000000000	0.0601417018540450	0.0311839231306286	9.8158277928161919	-0.1671990013178853	-0.0440006453831887	0.3119756499492467	
+0.3320000000000000	0.0599172487950799	0.0350254965581277	9.7679289224883927	-0.1257057086852203	0.1702172237083449	0.1363024107992384	
+0.3330000000000000	0.0588920899288691	0.0162622473413415	9.8079007756274557	-0.0763802334378752	0.0627192666226723	0.0944059896969695	
+0.3340000000000000	0.0704426130505714	0.0244627997925984	9.8040599338295138	0.2221723640928332	0.0057448522254052	-0.0598714145469913	
+0.3350000000000000	0.0522604410551405	0.0057019356806632	9.7938348276526188	0.2279574935735369	-0.2365586689639568	0.0732237361367453	
+0.3360000000000000	0.0773531922229228	0.0324441785157922	9.7868609963202076	-0.0370890522964215	-0.0568990242407368	0.0970540444710466	
+0.3370000000000000	0.0559258159630427	0.0182917158376898	9.8110938282821074	-0.0334512407912525	-0.1750557707810853	0.0463487034862890	
+0.3380000000000000	0.0693195011248290	0.0381964816817028	9.8042121684743293	0.1139876657491940	-0.3259977196607817	-0.0791211861396744	
+0.3390000000000000	0.0579227480884649	0.0099475838247528	9.8044423273899994	-0.1071558026914669	-0.0226835762460386	0.2235279145571719	
+0.3400000000000000	0.0616562958724505	0.0301389023422804	9.8197401855416615	0.0274184120387179	0.1165604171744288	-0.3102014600295727	
+0.3410000000000000	0.0627110467648350	0.0264016808228578	9.8143568271174537	0.1325051187182992	-0.3082443586350498	0.3268557887079738	
+0.3420000000000000	0.0459866348724153	0.0172561332106045	9.7964235459507290	0.2460636673775221	-0.0572018523771861	0.2656122728714359	
+0.3430000000000000	0.0575900155082415	0.0146834343083023	9.8033904824255629	0.0316145385986135	-0.1406216954352641	0.0328255873041794	
+0.3440000000000000	0.0706551456243130	0.0313315834659567	9.7943035716615316	-0.1625004438741331	0.1914945179293573	0.1251992492074649	
+0.3450000000000000	0.0506823664832824	0.0239958079575794	9.7938592736173860	0.1553000037029185	0.0589534820568147	-0.1940021596713795	
+0.3460000000000000	0.0396096951727746	0.0222980453564991	9.8073392678942906	0.0342481294492818	0.1441328944190059	0.1528195779488581	
+0.3470000000000000	0.0787093614349113	0.0390639791130810	9.8043119756123165	0.1441618477070962	0.2250851634993732	0.2386868950481976	
+0.3480000000000000	0.0613106612936371	0.0144512413084763	9.7845861419592914	0.1075323378657518	-0.1273827878159095	0.0956500663918951	
+0.3490000000000000	0.0690193469742762	0.0215746083156687	9.7841894627658270	-0.0632016926440693	0.1852167609911042	0.2505528559469897	
+0.3500000000000000	0.0773872845575758	-0.0059795691690653	9.8164642803846291	-0.0845138408260114	-0.4421779935258911	-0.0829264844777417	
+0.3510000000000000	0.0773803557265586	0.0181664180224912	9.8041396178669284	0.0086843345623050	0.0154759978342620	0.1030086889252491	
+0.3520000000000000	0.0526002757050331	0.0110527796205409	9.7825909805428850	-0.0339065243486177	0.1921751564184228	0.2426956895163965	
+0.3530000000000000	0.0763119984955780	0.0289723339841790	9.8078010482764739	-0.2042224724577080	0.1319827766781338	0.0558385508773299	
+0.3540000000000000	0.0547231410494111	0.0136801793086517	9.8091668622685493	0.0923620512716588	-0.0069156596968476	-0.1440988670117330	
+0.3550000000000000	0.0516354503495277	0.0395387050412509	9.8073029402330896	0.1340691759375862	0.0610812597335138	0.1386414546202496	
+0.3560000000000000	0.0499863027168348	0.0109123906361173	9.7938240571732074	-0.0321891604695387	-0.1257476834719529	0.1787274585403756	
+0.3570000000000000	0.0385457178799814	0.0156015675239559	9.7754123834664739	-0.0200019053838056	-0.0757637023209271	0.0003512595167702	
+0.3580000000000000	0.0517432680136386	0.0278548942937190	9.7957126281818514	0.0638121703652655	-0.0449341953881128	0.0729195454239252	
+0.3590000000000000	0.0533483702863673	0.0386152081480931	9.8022373228885229	0.0809750303529679	0.0450317446364747	-0.1187130827960408	
+0.3600000000000000	0.0506531114846322	0.0419732486797837	9.7882234761412086	0.2054831084478632	0.2351374042875173	-0.0851540460992714	
+0.3610000000000000	0.0581622464179081	0.0256334250326441	9.7956013858843516	0.0820450313109318	0.1559912075171876	-0.3373653423834820	
+0.3620000000000000	0.0676669813602160	0.0034300472940977	9.7890095341915213	0.2657502762720649	0.0133024887388883	-0.0747812416793233	
+0.3630000000000000	0.0736013362322940	0.0401379199595432	9.7833167628152378	0.1908715298716572	0.1811739655502959	-0.0625309936466366	
+0.3640000000000000	0.0571583561120928	0.0387903118784696	9.8155502433513320	-0.0345440874606138	0.2308359546636809	0.0340369400127591	
+0.3650000000000000	0.0767834230619468	0.0448274371600968	9.7938923636870658	0.1414672227154413	-0.3153751629072747	0.1458626602586144	
+0.3660000000000000	0.0759224178621596	0.0097321042896947	9.7997048076065472	-0.1320016290231021	0.1387989766253734	-0.0075366499463231	
+0.3670000000000000	0.0411090899424552	0.0171921584299145	9.8126066750419874	0.0159666821687228	0.4374037026740099	0.0263210567984533	
+0.3680000000000000	0.0643916074223981	0.0241404337485319	9.8084727924103419	0.2835432593944226	0.1164390588797063	-0.1436963039302160	
+0.3690000000000000	0.0644094366725611	0.0047929875956223	9.8014221485262318	0.0824028599517902	0.0193078318706780	-0.1399918167571591	
+0.3700000000000000	0.0630644249185915	-0.0002568671271306	9.8118941852080503	0.2653395148906298	0.1360793605201970	0.1149141376522788	
+0.3710000000000000	0.0522181913967682	0.0120449927443745	9.7801073403571390	0.2420940494895320	-0.0423944575062770	-0.0199822053595733	
+0.3720000000000000	0.0657306271809788	0.0162292152421407	9.7938464725904808	-0.1185044735907688	-0.1240644920637332	0.1511479426885687	
+0.3730000000000000	0.0783597955593956	0.0132581077045689	9.7879039986469234	-0.3082020343867022	-0.1875170689648817	-0.0584951583335575	
+0.3740000000000000	0.0597050368056661	0.0350119498210322	9.8186227190134101	0.1445042464819030	0.1122587737505873	0.1949697924873074	
+0.3750000000000000	0.0592825611279341	0.0153486508339212	9.8001210961185770	0.1440465785509386	-0.1784382021894337	0.1266816728680163	
+0.3760000000000000	0.0475110532101955	0.0205969674721656	9.8099238096535935	0.2358139561746452	0.0995507937705815	0.0986227865069893	
+0.3770000000000000	0.0705517623842578	0.0122387588010195	9.7872400392473704	-0.0704887981436289	0.2278968521514028	0.1411456296779172	
+0.3780000000000000	0.0379277668080598	0.0110007641045886	9.7937528950759205	0.1635000718521277	-0.0447232824682487	0.1920904964910094	
+0.3790000000000000	0.0606309008621761	0.0330015418391477	9.7932628475581058	-0.0091448276990540	-0.1330378928241006	0.2137087157363372	
+0.3800000000000000	0.0556942170428711	0.0279368790067768	9.7899946325013101	0.3837886690909376	0.0571142274221428	0.2792348053320223	
+0.3810000000000000	0.0448580256619423	0.0200578043581766	9.7988332557495568	-0.0554486545442429	-0.1075180942945874	0.2805722878395433	
+0.3820000000000000	0.0583249924005226	0.0237571022553446	9.7993966054117791	0.0643297166313133	0.0031798396139074	0.0425710850890319	
+0.3830000000000000	0.0709296566170197	0.0266400970604794	9.8085818641026261	-0.0611906710306385	0.1998854892230925	0.1243156251952629	
+0.3840000000000000	0.0663927515965331	0.0305347587138068	9.8203865268345023	0.1309619778903020	0.0839082697240666	0.2076467935107323	
+0.3850000000000000	0.0684846824179436	0.0378249060221712	9.7684297365022132	-0.0562555048281499	-0.2079755120741409	0.1841036333751986	
+0.3860000000000000	0.0414381898184793	0.0205622213417769	9.7835854433432896	0.0434469930162164	-0.0086991762277106	0.0641926372041544	
+0.3870000000000000	0.0564687261593066	0.0072219999235001	9.8014711554608596	0.1022084524520771	-0.1507786315568568	0.0539995443032464	
+0.3880000000000000	0.0512777675559486	0.0200978590781425	9.8048952041953825	0.4240638548700492	0.0501528951781933	0.2683892282329357	
+0.3890000000000000	0.0525933580427214	0.0312525530435653	9.7919388237440099	-0.1094486417891965	-0.1031679400595798	0.0508017933587651	
+0.3900000000000000	0.0580731565752189	0.0359871411815979	9.7925756166438145	-0.0159003095167329	-0.1510230400104300	0.0290466993050075	
+0.3910000000000000	0.0394103143190297	0.0195522649328677	9.8099233820810348	-0.1954856164871294	-0.1665688327645257	-0.1718388218594008	
+0.3920000000000000	0.0603644465122540	0.0441744472515219	9.7890487305236373	-0.1315102631135878	-0.1498107788551080	0.0774360270248305	
+0.3930000000000000	0.0590133662562366	0.0142711640231591	9.7973206030355247	0.0179145279630781	0.0090319815582387	0.1839461859983109	
+0.3940000000000000	0.0643928580710709	0.0420364146098018	9.7895540610221801	-0.0851502366756837	0.0839712460269496	0.1342852357195635	
+0.3950000000000000	0.0612185724525952	0.0239855178275402	9.7943123993145651	0.1090925026614709	0.1526619321968615	0.0070497137105523	
+0.3960000000000000	0.0625104886364064	0.0053077016927008	9.7953973660143223	-0.2104011298630807	0.2697901457006494	0.0506137306310232	
+0.3970000000000000	0.0685306072053119	0.0290160903506152	9.8187365023724951	-0.0457390641805565	-0.0283748446287085	-0.0445730813440815	
+0.3980000000000000	0.0733842644254806	0.0190971427985128	9.7900180999776438	0.0440311538640704	-0.1776604122044141	0.0341267226226243	
+0.3990000000000000	0.0665034029571820	-0.0010011321380509	9.7883485263155059	0.1214384315095687	-0.1237833378169364	0.0470497354878061	
+0.4000000000000000	0.0562204442697853	0.0390694350148544	9.7989694432453760	0.2208337635037177	-0.0176435177597623	-0.1373220810595316	
+0.4010000000000000	0.0650686730292786	0.0267958513545441	9.7954355997635290	0.1739142236275394	-0.1240162343019904	-0.1620073605107015	
+0.4020000000000000	0.0628876130661449	0.0138926801295446	9.7935934115371222	-0.1297845520579241	-0.1782469970136300	0.0678644717540545	
+0.4030000000000000	0.0624242764286672	0.0151283963377737	9.8039069389273674	-0.1776006319305924	-0.0348766633182621	0.3444010687713298	
+0.4040000000000000	0.0592812187457382	0.0113153917697714	9.8051937148934787	0.1806073965971706	0.0469313011133206	0.2727780346093013	
+0.4050000000000000	0.0663219297969936	0.0231604624151408	9.8019433725775613	0.0395117008060918	-0.0202447528912599	0.2333405426236761	
+0.4060000000000000	0.0843759762028080	0.0303072724253901	9.7917496020514161	-0.0743604163554125	-0.0083396799852007	0.1250964283232612	
+0.4070000000000000	0.0512994236622092	0.0457716199253578	9.7768188585037077	-0.0437152864228023	-0.0137295816432583	0.1539661950133012	
+0.4080000000000000	0.0776836836779002	0.0339554471692228	9.8271136521768874	0.1192591450994739	0.0853415401806321	-0.1284612788594244	
+0.4090000000000000	0.0592542418119364	0.0190736069221692	9.7908783336778189	0.2954774332682933	-0.0412855091027146	-0.0837818968759827	
+0.4100000000000000	0.0677129012530757	0.0164614563979048	9.7859464514634205	-0.1965440713729540	0.0456740448799095	-0.2201069539135220	
+0.4110000000000000	0.0720929783786725	0.0383006530316049	9.8014436918217349	-0.0277413056139776	0.0452667354570543	0.0982174552875204	
+0.4120000000000000	0.0634770404571703	0.0429116846297856	9.7953957747301743	0.0135425777541431	0.0237620762894826	0.1726243365211922	
+0.4130000000000000	0.0727084224856826	0.0290271013053483	9.7895710648676850	0.3877032291045833	-0.2230954192318238	0.0871820315379319	
+0.4140000000000000	0.0573695079878618	0.0292439369099234	9.8045670590533653	-0.1259414376546886	-0.0200504077103654	0.0041603594384296	
+0.4150000000000000	0.0532688697369723	0.0095163308251839	9.8138446095476315	-0.0598711564682883	0.0469706221802849	0.1290755137783738	
+0.4160000000000000	0.0580137649386311	0.0328843133298717	9.8077806478544378	-0.1480982423798621	0.1100009369122494	0.2966165262145545	
+0.4170000000000000	0.0691244320738625	0.0342332660174113	9.8060266342029880	0.0530340672078778	-0.0810355108377639	0.1124871183725951	
+0.4180000000000000	0.0666893088605984	0.0010150747380285	9.7954142015202894	-0.1842849032250918	-0.0572144619064716	0.0802800834391926	
+0.4190000000000000	0.0537159148546151	0.0158953529309972	9.7708883706624974	-0.1533287728297457	0.0312455308555449	0.1407503788867828	
+0.4200000000000000	0.0496021327976791	0.0204199050010689	9.8110586466954697	-0.0184188414309304	-0.2429580131522126	-0.0664235900950326	
+0.4210000000000000	0.0482818792900951	0.0216903012053266	9.7962271198685844	0.2550652146816086	-0.0315827802989445	-0.1428800909091405	
+0.4220000000000000	0.0591839030559812	0.0164242656013810	9.7980637804165465	-0.1043691528737696	-0.2193119607990434	0.2502927185568037	
+0.4230000000000000	0.0654930438142938	0.0182177339726554	9.7988280771915708	0.4046317017549492	-0.0324288070296999	0.0420910181713293	
+0.4240000000000000	0.0756127067760551	0.0424931596980277	9.8046955818855981	-0.0527956033784899	-0.0527800392991129	0.1314641539707166	
+0.4250000000000000	0.0558810827911550	0.0355185080087454	9.7912960335773800	0.0063309657185375	0.0016089799624128	-0.0309797063935034	
+0.4260000000000000	0.0589969146880866	0.0055118321819488	9.7839098287266371	-0.1527754313271533	-0.2686267414013425	0.0239386650032185	
+0.4270000000000000	0.0443644996109493	0.0252092865012591	9.7976683203335089	-0.0001458916493108	-0.0951033892005070	0.1510540148261691	
+0.4280000000000000	0.0626947907793249	0.0415611520129527	9.8014551685325930	0.2597354685656293	0.0390035414725892	-0.0539315524286079	
+0.4290000000000000	0.0584155810420999	0.0205034535470077	9.7870234601357957	0.0469994703357534	0.0050938162477573	0.2147090550176091	
+0.4300000000000000	0.0530298643300212	0.0237284878085291	9.8165296493138623	0.2102553305008380	0.3094534403877639	0.0214838825655161	
+0.4310000000000000	0.0717945915869533	0.0307576793215707	9.8164049246295537	0.1222781721108179	-0.0013219157279175	0.1687149770992209	
+0.4320000000000000	0.0570761615532010	0.0342563391785376	9.7885475443081233	0.0836798597913714	0.0115726216322316	0.0720748728015949	
+0.4330000000000000	0.0724875553211718	0.0277658984318558	9.7867377579765655	-0.0883691703642182	-0.0628958597058837	-0.0690980076689423	
+0.4340000000000000	0.0600846335443531	0.0455362141185470	9.7788899224573704	0.0964012595497441	-0.1198072243920590	0.0003507488147990	
+0.4350000000000000	0.0363488584397510	0.0292654398380225	9.7853984697769079	0.1356915127836529	-0.1730261683272049	0.2164411471495971	
+0.4360000000000000	0.0496015264662313	0.0095613185748436	9.7987164364769050	0.0377930133005457	-0.0240391006772263	0.0342628038650751	
+0.4370000000000000	0.0401244305895801	0.0417823549414651	9.7905574357036400	0.0830307246965558	0.2062788036305379	0.0798018630327931	
+0.4380000000000000	0.0714818566979575	0.0221412714400442	9.8061961099567938	-0.1145413699513035	-0.1642002470886094	-0.0405523991484400	
+0.4390000000000000	0.0660726638340904	0.0391536278767547	9.8096608321883831	0.1082156277137900	0.0909306763793559	0.1947941024503003	
+0.4400000000000000	0.0629884473771895	0.0142622305620980	9.7934436245690293	0.1637788131674028	-0.0760357207908076	-0.1552001489168386	
+0.4410000000000000	0.0607306117702080	0.0279731046620729	9.8071166295392675	0.1816054944528253	-0.2242611762764337	-0.0586742481024962	
+0.4420000000000000	0.0603249698668473	0.0277075136713553	9.7940777319315568	0.1571534036946566	0.0282391615887908	0.4085317160029533	
+0.4430000000000000	0.0711194967204969	0.0043201038010469	9.7971728469202262	0.3422931662613327	-0.0585381418682722	0.1026302755205240	
+0.4440000000000000	0.0683170134458227	0.0323860488590837	9.7856726862539567	-0.0463939674805733	-0.1491631875218963	-0.0348083753994001	
+0.4450000000000000	0.0636075986830991	0.0399593428022723	9.7874051916435043	0.0634072471027319	0.0447004890681556	0.1661736670044519	
+0.4460000000000000	0.0575747021719539	0.0463580006330401	9.8038515519207579	0.2063597131073337	-0.0312350395253639	0.0607493991441592	
+0.4470000000000000	0.0758496036280284	0.0423588279182813	9.7737759578730650	-0.1007796116282443	-0.1464725971125475	-0.0657251159281940	
+0.4480000000000000	0.0498596591978262	0.0149212391518246	9.8197071884163609	0.1999135390973620	0.0423907019512704	0.0113703316506190	
+0.4490000000000000	0.0761091824255310	0.0434386396268854	9.8157609087348003	0.0990390076854449	0.0934470180140859	-0.0587654094006639	
+0.4500000000000000	0.0759633298436589	0.0173223964925123	9.7881785767430110	0.2731416260812575	-0.2006268716359636	0.0002581383987182	
+0.4510000000000000	0.0605552405006565	0.0415937498759655	9.7765777307863839	0.0248164371716582	0.1980056501667066	0.1761751086185550	
+0.4520000000000000	0.0450605662875883	0.0114270614551877	9.7914662806164525	0.1271396366463839	-0.0525475706660621	-0.1681976219686100	
+0.4530000000000000	0.0544624900888852	0.0385171994968140	9.8129416567429573	-0.1299263811655614	-0.1448345567558438	-0.2050244728142503	
+0.4540000000000000	0.0545264861373217	0.0249367923073932	9.7939707287079347	-0.0004577386905142	0.0508449700182146	0.0254511713235547	
+0.4550000000000000	0.0916383233158864	0.0467324137596346	9.7983566465612526	0.0219589391139929	-0.2065898619374104	-0.0438772463499605	
+0.4560000000000000	0.0868727794926873	0.0263931158565918	9.8021369357347261	-0.1296931548591069	-0.2400535127825496	0.2410013318742705	
+0.4570000000000000	0.0659320715167907	0.0210805840575512	9.7865567053772491	0.1180823641824536	-0.0321650029530044	0.2013249513744789	
+0.4580000000000000	0.0917906049538326	0.0357192110603240	9.8116050805995627	0.4005517292036506	-0.2738561550066582	0.0837004225670799	
+0.4590000000000000	0.0394929200995841	0.0049451674323256	9.7934038304508455	0.3598762811479043	-0.1077441362024542	-0.0662051578396432	
+0.4600000000000000	0.0415612401109509	0.0063316264121809	9.7893791178197613	-0.0268437152295911	-0.1667173053803766	0.0535899280986211	
+0.4610000000000000	0.0729258872340383	0.0150118866207338	9.7801909531947846	0.1178738222234769	-0.1807842520669606	0.1620226933846390	
+0.4620000000000000	0.0577839496009872	0.0219719118928661	9.8037077905270209	0.1379464880552649	0.0852894958843346	0.0443154513458955	
+0.4630000000000000	0.0343066123421734	0.0235224323204686	9.8029650641344812	0.1907828409506180	-0.0025901613246857	0.1987129186576255	
+0.4640000000000000	0.0570443338858712	0.0362656142463751	9.7859410310804638	0.0869489346150110	0.0970208603400304	-0.0484559378210441	
+0.4650000000000000	0.0502031729166715	0.0296540466251690	9.7964467931919312	-0.0596929827555771	-0.1928337023373159	0.3224284750896859	
+0.4660000000000000	0.0705463463983392	0.0360475465979786	9.8063888044220722	0.1852904019219682	0.0134267632936533	0.2459997162453597	
+0.4670000000000000	0.0695273738993946	0.0124335906535247	9.7971857801904960	0.1314423425635786	0.1119893266495083	0.2560165205529761	
+0.4680000000000000	0.0661081505468815	0.0320721305523168	9.8023011650791396	0.1243609223965561	-0.1197170592817256	-0.1829549934763308	
+0.4690000000000000	0.0493170269621761	0.0370839638338999	9.8096871711163018	0.0190724447048006	-0.1447312246830920	0.0580333872877531	
+0.4700000000000000	0.0752279598531150	0.0306197054450087	9.7843805598844220	0.0555961788046570	-0.0012646626999006	-0.0462937433267055	
+0.4710000000000000	0.0742206947326324	0.0238264640322648	9.8070355602794272	0.1124210805589328	-0.0707910014958582	0.3181419793532134	
+0.4720000000000000	0.0601590356760752	0.0395131801054951	9.8027182421242181	0.0556586269856884	-0.1540259992726218	0.3157008033487848	
+0.4730000000000000	0.0563772413950678	0.0338380183214269	9.8093408650544553	0.1160297779227112	-0.3734983549455893	-0.0517925993052738	
+0.4740000000000000	0.0490908846042196	0.0042085147731482	9.7718718309151598	0.2572728954164220	-0.1243272984730732	0.1150290624300624	
+0.4750000000000000	0.0707478622968138	0.0197954756465226	9.7906536905587611	-0.0402405014967510	-0.0885755249732783	-0.0589578807990417	
+0.4760000000000000	0.0744595902803201	0.0059962595559571	9.7842837638781894	0.0371662029666023	0.1649044110350616	-0.0190087695819359	
+0.4770000000000000	0.0851077965824150	0.0124687882160762	9.7945759762776969	0.1314984750586504	0.0228513439593402	0.2273869213611517	
+0.4780000000000000	0.0615711258472438	0.0274254688372600	9.7977680807646248	0.1118930905642666	-0.0880117085312854	0.1577288977429787	
+0.4790000000000000	0.0567805390472234	0.0213796499539354	9.7869115379877645	0.0450038232203941	0.1442562890464822	0.0038154209035544	
+0.4800000000000000	0.0610144705146796	0.0118413521138733	9.7866813335987572	-0.0042358623997162	0.0475332571444579	0.1778893684504772	
+0.4810000000000000	0.0444832521275364	0.0308843722372248	9.7959393485010544	-0.0654610920247018	0.2666588895382251	0.0580030447456264	
+0.4820000000000000	0.0567371293267831	0.0114240163473571	9.7882070755399333	0.3228538942750718	0.1493579311375674	-0.0988339137526563	
+0.4830000000000000	0.0682559258953657	0.0296123346213004	9.8183228708994523	-0.0337542425896457	0.1616901567234068	0.0893905618540070	
+0.4840000000000000	0.0558623213887263	0.0127694739048621	9.7956023730444706	0.1327835073075439	-0.2045012936293063	-0.0148360624930333	
+0.4850000000000000	0.0709797742823446	0.0213693195014594	9.7988986465560153	0.2577217002536284	0.1256298008041241	-0.1486312509054149	
+0.4860000000000000	0.0583307394678076	0.0193205610304157	9.7764013647930579	-0.2030349837009152	0.1190001273294193	-0.0331051943179919	
+0.4870000000000000	0.0525030097505417	0.0141743624652460	9.8066367022033720	0.0149688320081244	0.0993607445005639	0.0630657536108059	
+0.4880000000000000	0.0547424677402474	0.0270155898099876	9.7939906110253308	0.2798727447659971	-0.0938239865767943	0.0955375494886129	
+0.4890000000000000	0.0464781628162194	0.0286692006524439	9.8275605350582822	0.0308710154981646	-0.0519562276236467	0.2006721292077357	
+0.4900000000000000	0.0692145460992541	0.0431893227699799	9.7927618212857581	0.3004999272589667	-0.0174766970094597	0.1691764772189276	
+0.4910000000000000	0.0867600876897697	0.0287344133437705	9.7866933330377570	-0.0021078726867054	-0.2305867759727346	0.0582204110852633	
+0.4920000000000000	0.0761339998214679	0.0270609753387213	9.7857881336518737	0.2264126508235610	-0.2471678926416734	-0.2461246144596060	
+0.4930000000000000	0.0637800677450039	0.0098422110297966	9.7756991208823969	0.0003050723131032	-0.0725657964531496	0.0373289439382042	
+0.4940000000000000	0.0778506211328799	0.0277616029125047	9.7836547675376071	0.1121020427573367	0.0556260425526199	0.1492467757881775	
+0.4950000000000000	0.0475179951007894	0.0185289747250073	9.7976897846423601	0.0881517870959424	-0.2259305836093201	-0.1969157128645448	
+0.4960000000000000	0.0740576608821182	0.0185536386858227	9.7934503065557550	0.0711305128319740	0.0934798867941509	0.0494557410173955	
+0.4970000000000000	0.0469491000671169	0.0236877629611090	9.7879872199908853	-0.0507278996892520	0.0859033638422772	-0.1348147487166272	
+0.4980000000000000	0.0724902994625418	0.0367790073701369	9.8068442883102200	0.0048907292003082	-0.0963580870199613	-0.1543130349092855	
+0.4990000000000000	0.0464676927986370	0.0312443480050539	9.7873523316082238	0.0262412752779542	0.0206374946424586	0.1775983245584745	
+0.5000000000000000	0.0577881587186757	0.0156300715979843	9.7980410915362022	0.0450849155612506	0.0074164275941512	-0.0596076821618429	
+0.5010000000000000	0.0645240832527097	0.0319824669335566	9.7821724880637735	0.0534480956057491	-0.0159354230945620	0.0868774263813085	
+0.5020000000000000	0.0564360346324668	0.0235054865032049	9.8072290641047903	0.2721588163940790	0.1290761348532219	0.3051537947199988	
+0.5030000000000000	0.0479830635506778	0.0301785842774227	9.7831719178492378	0.0301215281798248	0.0125766239164847	0.0036931531360975	
+0.5040000000000000	0.0829510001660421	0.0438074784935699	9.7956950474277171	-0.2376711291351151	0.3168700034468031	0.0136179373314408	
+0.5050000000000000	0.0588014219718433	0.0330714288924016	9.8015519618831153	0.2572274906849806	0.1565243850152746	-0.0105787401888346	
+0.5060000000000000	0.0691061002772000	0.0423436573277903	9.7885873032410835	0.1505639958766101	0.1246466860965112	0.3576372957586542	
+0.5070000000000000	0.0508808213410235	0.0242485844804787	9.7730285707598732	-0.1540832540244927	0.2540918796076624	0.3666214710482740	
+0.5080000000000000	0.0661508367124528	0.0260019090499486	9.7929047460827707	-0.3416004057603153	-0.0294557939454498	0.3129214410976006	
+0.5090000000000000	0.0710112234861186	0.0052008138942689	9.7722664840507214	0.0157673608737812	-0.0116783616789992	0.0793763931292362	
+0.5100000000000000	0.0608063983649447	0.0361493524222311	9.7973345101785139	0.1524480966398464	0.0704338116996019	0.1872638606632054	
+0.5110000000000000	0.0444960467657797	0.0059264618257993	9.8035778703992680	0.0474173140442121	0.1787329000150182	-0.0084960591795947	
+0.5120000000000000	0.0659050232740876	0.0258518146332792	9.8025296566117142	-0.1048548951960653	-0.1761579519882394	0.1601070793179662	
+0.5130000000000000	0.0370825616865300	0.0383351436518657	9.7909052297437142	0.0986502117647508	-0.0086974306572717	0.0787771666780119	
+0.5140000000000000	0.0388112415351103	0.0115570480658903	9.7890936757174813	-0.0508837980201227	0.0913037809799551	0.1954931659044721	
+0.5150000000000000	0.0651665006982445	0.0175927336494753	9.7895730521594544	-0.0023348977801947	-0.0864983852421777	0.0485832769939569	
+0.5160000000000000	0.0435688017918718	0.0324999219796964	9.7997890474617790	0.1226526113195746	-0.1475280565958748	0.0964518670239130	
+0.5170000000000000	0.0575318617173807	0.0168017443976434	9.8031875874729923	-0.1713113782012499	-0.3070612497493576	0.1050479023487091	
+0.5180000000000000	0.0417517006768272	0.0263596502520346	9.8022744503856085	0.3210621446954191	-0.1586728477986852	0.1520698149208150	
+0.5190000000000000	0.0973120203917610	0.0098413012081334	9.7969791509294701	0.1146867180841867	0.0712558607050454	0.3696267027864926	
+0.5200000000000000	0.0594368761117717	0.0346384957779250	9.7895866103711615	0.1077176203024956	0.0997440056924018	0.3332058103601883	
+0.5210000000000000	0.0455212093864457	0.0168632225105835	9.8090186177873857	-0.0751678334058616	-0.0244756052013177	-0.1471527081635490	
+0.5220000000000000	0.0548311996466468	0.0162984273779465	9.7681988328204081	0.0973548785927024	0.0581698119577184	0.4377407787988036	
+0.5230000000000000	0.0487225167718949	0.0511246317254557	9.8069932207225552	-0.0096035448172313	-0.0797732953924716	0.0991407401019909	
+0.5240000000000000	0.0606785109463665	0.0021393380169367	9.7975583228464611	-0.2178812046937869	0.1585111617688358	0.1611888444158863	
+0.5250000000000000	0.0498424699046181	0.0280816355350956	9.8134627119759017	0.1460755129263838	0.0836479787252370	-0.1506575374342969	
+0.5260000000000000	0.0787998055246470	0.0336322234868651	9.8001239948415044	0.1102881743549879	0.0271035504316747	-0.0002186216275085	
+0.5270000000000000	0.0660949366632914	0.0123011118344019	9.7904262642592386	0.0282096579648650	0.0405567758442090	0.0633112201219181	
+0.5280000000000000	0.0574215097705723	0.0313047556527937	9.8111007130556338	0.0145912349071920	0.1454932862876857	0.0147115331501120	
+0.5290000000000000	0.0720472458734972	0.0129873377671831	9.7883443616244090	0.1697641507794405	-0.0742452650364162	0.0754570126589061	
+0.5300000000000000	0.0507470304336146	0.0257431040634844	9.7846258660204590	0.1947663360282250	0.0289466093142076	0.0599139782373284	
+0.5310000000000000	0.0598411200890824	0.0259245297595960	9.8076709493123850	-0.0943392180664174	0.1034958601187616	0.1577960834553008	
+0.5320000000000000	0.0659324414305228	0.0130706456656749	9.7895609663612433	-0.0017922344136713	0.0882318750011508	0.0366212712620737	
+0.5330000000000000	0.0503075654379890	0.0120650413817780	9.7948745001338917	-0.0108771865558294	-0.1181772397799793	-0.0147721266632265	
+0.5340000000000000	0.0772923535877572	0.0352986128335510	9.7799790268793849	-0.0506290134697165	0.0931080102897750	0.1430495183214756	
+0.5350000000000000	0.0625368330737933	0.0278775646345483	9.7899077948968198	0.0992582307470924	-0.0644990158125152	-0.1983201975801673	
+0.5360000000000000	0.0474090578231458	0.0260299001542767	9.8072052416400819	-0.0958337891864139	0.0390665520260279	-0.0932607812245003	
+0.5370000000000000	0.0460536065400882	0.0290106500987503	9.8069310189123975	0.0375548256008499	0.0050507367072740	0.1482821678003954	
+0.5380000000000000	0.0549365671472077	0.0173748656663960	9.8116099515199338	0.0831854314802674	0.0175908201216116	0.0558293093579198	
+0.5390000000000000	0.0643009181962879	0.0078389305838445	9.7699049019743143	0.2041968913794545	0.0940225018474457	-0.0231449369140954	
+0.5400000000000000	0.0556327496862504	0.0172267061111656	9.7887680629743592	-0.0598964659538888	0.0487064248755945	0.0848196951932508	
+0.5410000000000000	0.0647689418291943	0.0391744826459061	9.8169061685418395	0.2227441385529645	-0.1829260830665823	-0.0836535720943769	
+0.5420000000000000	0.0505437784717626	0.0278592711739975	9.8079274324839076	-0.1569849493862884	0.1368315000954068	0.1440872334381088	
+0.5430000000000000	0.0531845107994084	0.0068722112802599	9.7747153303267780	0.3169469574209166	0.2378240615458411	0.0813862366815346	
+0.5440000000000000	0.0457862598910912	-0.0035644510932101	9.8204359590633885	0.2716877878974009	0.1816044323781439	-0.1939087933819219	
+0.5450000000000000	0.0585918805023741	0.0133386066543255	9.8103561304847151	-0.2134985948542832	0.1062947289465138	0.1960246593058903	
+0.5460000000000000	0.0594497303704820	0.0287354591007034	9.7940163495754042	-0.0417911890867154	-0.1596909094366874	0.0566776382177146	
+0.5470000000000000	0.0421957718271285	0.0002731099830483	9.7986760399654464	-0.1222716432687396	-0.1997835282261861	-0.1319452039152148	
+0.5480000000000000	0.0585424853032775	0.0191402747005303	9.7979584070508157	-0.1622725769891356	0.0019408362342050	0.1317248093680454	
+0.5490000000000000	0.0559978748775729	0.0196903296769507	9.7991052712457520	0.1355096868954269	0.2315797423778800	0.3892394479562642	
+0.5500000000000000	0.0429716548490623	0.0162701365526869	9.7840369664773643	-0.0497055344611311	-0.2361198759465184	-0.0632719708054491	
+0.5510000000000000	0.0638092765444954	0.0296201972130948	9.8009709498056417	-0.0020397918316171	-0.2157683452956537	0.1191971399900497	
+0.5520000000000000	0.0522320370725204	0.0198132020750420	9.7983950486027265	0.0496142772753861	-0.0341369485942523	-0.0379257618220621	
+0.5530000000000000	0.0450254873830227	0.0173595648466282	9.8031687404286902	0.0161544392108298	0.1810698942042269	0.2319769924765044	
+0.5540000000000000	0.0624692978365202	0.0393953751099452	9.8117267264805239	-0.1566117968303632	0.0856429730561807	0.1743679558147458	
+0.5550000000000000	0.0826449703611006	0.0360346861603514	9.8246562554495416	0.1027852168106130	-0.1349240187160985	0.2247934715090351	
+0.5560000000000000	0.0547817384695180	0.0278621122758035	9.8118861689347341	0.0802623235703559	-0.0768829661356072	0.1179205003217338	
+0.5570000000000001	0.0669928729945857	0.0272434789885443	9.7947371652165707	0.1221925756932681	0.0276015680100644	0.0956686661570309	
+0.5580000000000001	0.0612218851049959	0.0336464339253335	9.7965817448224168	0.3050408657208525	-0.1747611298681445	0.1698551757564125	
+0.5590000000000001	0.0442650826667188	0.0200426709770143	9.8199868941872008	0.0504377402467883	0.0913376075194476	0.0259892876132663	
+0.5600000000000001	0.0696058279666720	0.0191996016680573	9.7958887328652633	-0.1017439155838343	0.0799735254302992	0.0516718189706318	
+0.5610000000000001	0.0623309627729634	0.0191975076020926	9.7954522622256786	0.0699339513949770	-0.2769149679816418	-0.1738049006370915	
+0.5620000000000001	0.0539682299092335	0.0346592783904080	9.7966462504307827	0.2755321443515749	0.0319575880069596	-0.0900079457100974	
+0.5630000000000001	0.0897027592440218	0.0209065478137701	9.7952108808694121	0.1470766126350616	0.0368692523965787	0.3741022050623276	
+0.5640000000000001	0.0680858938581782	0.0165611105036375	9.8084983518709628	0.0398824191153707	-0.2773627116470446	0.1506873795754074	
+0.5650000000000001	0.0754568222547388	0.0069834445786298	9.8075576025744926	0.0980368413146070	-0.2047828760923752	0.0932049841172856	
+0.5660000000000001	0.0416321760561040	0.0077609473258151	9.7948471754390933	-0.0980220426112518	-0.2392995319373711	0.0255465586940046	
+0.5670000000000001	0.0571187056471421	0.0285484934067163	9.7900275266794239	0.0001329965579812	0.0881154231261759	0.0428294834353894	
+0.5680000000000001	0.0683401842087594	0.0242176663430834	9.8117357253143620	-0.0866587075785223	0.2132215066277200	0.0587733467072106	
+0.5690000000000001	0.0492921231849357	0.0359873723476072	9.7747976951536693	-0.0393729175544695	-0.0974192453459193	0.1444707929689165	
+0.5700000000000001	0.0436591321540855	0.0323111357514047	9.7926128491609621	0.0868872588959828	0.0189867852611050	0.0114292492106125	
+0.5710000000000001	0.0775391596397054	0.0069731976218887	9.8011341057174235	0.0176937149822076	0.0095637861381891	0.1542081432723589	
+0.5720000000000001	0.0624347368438457	-0.0023059606153488	9.7915903559522111	-0.1203125971572297	-0.2037708506809032	-0.0009252422472951	
+0.5730000000000001	0.0442492329169743	0.0060227600739896	9.8116856703350006	-0.0251736850945768	-0.1839651611797127	-0.0291559592323666	
+0.5740000000000001	0.0732579165253494	0.0159304809002664	9.7853933830241697	0.0399561323741255	0.2010504509562833	-0.0660740988773977	
+0.5750000000000001	0.0772308146461841	0.0221937076600607	9.8098094337443413	0.0537454166356623	-0.0548904477699010	0.1181580525284933	
+0.5760000000000001	0.0596486871630351	0.0219627822380125	9.7855266749691481	0.0484413771818728	0.0083591138029860	0.0464607796829372	
+0.5770000000000000	0.0785248720753844	0.0305287005544045	9.7853755845997270	0.0486052537447952	0.2018310811218834	0.1150008788650874	
+0.5780000000000000	0.0761918110545833	0.0109260505939443	9.8133459943111525	0.2774637866685080	-0.0222240777481410	0.0446645900793207	
+0.5790000000000000	0.0536731608780717	0.0115682955336287	9.7941620718092697	-0.1078947566689527	0.1600464844339714	0.0497974220486981	
+0.5800000000000000	0.0515688415431087	0.0249528719218626	9.7821479447758204	0.2774088495232132	-0.1374188174810353	0.2619663330938404	
+0.5810000000000000	0.0633213269391787	0.0229393407513684	9.7852428417581176	-0.0133513717148554	-0.1011240808319863	0.1971168192909286	
+0.5820000000000000	0.0494803055019387	0.0249247148946483	9.8031190033413260	0.2009567494397853	0.0530144098349271	0.1580712212763130	
+0.5830000000000000	0.0477140637186327	0.0176818277352864	9.7930950065413906	-0.0266956216746703	-0.0243112036525517	0.0757233188946532	
+0.5840000000000000	0.0559207748624056	0.0139979684175556	9.7945037771558336	-0.0621700373198191	0.0989420740084922	0.1072472444906913	
+0.5850000000000000	0.0566181761120599	0.0232034093688597	9.7881575006633650	0.1972184321372992	-0.0350673091371919	0.2482867367293440	
+0.5860000000000000	0.0658621871938464	0.0361051752349003	9.7887509538316202	0.0856137368582889	-0.0564141168493175	-0.0680189887345804	
+0.5870000000000000	0.0679205134814158	0.0323617655683898	9.8253509203132054	-0.2220915154534707	-0.2065183561497286	0.0722393580333248	
+0.5880000000000000	0.0754624433312686	0.0161260772437696	9.8220250748775513	0.0343796310982494	-0.1969657777465812	0.0056576159086419	
+0.5890000000000000	0.0657668802856355	0.0295259570207599	9.8095608217919903	-0.0484500359545981	-0.0505436383520258	0.2934930824152557	
+0.5900000000000000	0.0654021761810974	0.0226480638357869	9.7629977771355865	-0.3304674031797067	0.0033841430510027	0.1292762358246446	
+0.5910000000000000	0.0471893586768384	0.0069048230398562	9.7790688886412163	0.2449260505472557	-0.0443231555123457	0.1394042218557785	
+0.5920000000000000	0.0773661074238455	0.0185347158591759	9.7998489246467440	0.0952682546396020	-0.2565229208889210	0.0218317972431203	
+0.5930000000000000	0.0577701478098894	0.0082040290261327	9.7892860484789530	-0.1922953777106484	0.1471589676932477	0.1757091768843235	
+0.5940000000000000	0.0656321235612137	0.0329707421829153	9.7919041074187128	0.1603953310745309	0.0150943382547594	-0.0119830047373777	
+0.5950000000000000	0.0547753558263032	0.0213958191333855	9.8171604189467310	0.0408683932488376	-0.1927423728890449	0.0951699217667782	
+0.5960000000000000	0.0771782239511811	0.0169680643104704	9.7881095441968426	0.4314227964275775	-0.0382961571913799	0.0463912656574119	
+0.5970000000000000	0.0625418545806117	0.0245924219255317	9.8074610375605129	-0.1301890690431718	-0.0074988027140670	0.0334370485407029	
+0.5980000000000000	0.0762434765053824	0.0250901588281769	9.7839251539711007	0.2138004352274708	0.2106870729296028	-0.1062047225699521	
+0.5990000000000000	0.0572548146398482	0.0249899266355583	9.8120202613215390	0.5248246589783899	-0.1722775817397583	0.4656104654061617	
+0.6000000000000000	0.0591888220651727	0.0101591156802755	9.7984560806255505	-0.1123546253847789	0.0963904798007989	0.0664479255085576	
+0.6010000000000000	0.0665348945043475	0.0186537608354940	9.7728309765266594	0.2465914960694590	0.2817939483290149	0.1443285043266244	
+0.6020000000000000	0.0553434115508080	0.0674157659242022	9.8037641951072203	0.1548740529000897	-0.0666330536316259	0.1129807691280902	
+0.6030000000000000	0.0764760766676992	0.0314556434571010	9.8155062807977309	-0.0260180765578628	-0.3434428390249065	-0.1882111439941108	
+0.6040000000000000	0.0644471473066739	0.0406083119843782	9.8140407938369840	0.0170384354549104	0.1300030482070705	0.0786647546705394	
+0.6050000000000000	0.0574596306993987	0.0271203460724644	9.8052418052364541	-0.0994074329289109	0.1853387782037127	0.0205922501097115	
+0.6060000000000000	0.0543855487622409	0.0374552978565950	9.8021425603467236	-0.0621124449802922	-0.0799298170760838	0.2683279048120953	
+0.6070000000000000	0.0600797081983780	0.0120011818737515	9.7960273748716240	-0.0236994963414096	-0.1739453248753008	0.3059653855979146	
+0.6080000000000000	0.0719305096648718	0.0273279675004425	9.8053016863554010	0.2028434986766040	-0.1384997405483733	0.1461291666648919	
+0.6090000000000000	0.0732515957940143	0.0424941810582385	9.8009617196175114	-0.0164766653943861	0.0355009097467072	0.2956489375023236	
+0.6100000000000000	0.0977987112399062	0.0229605960192385	9.8059333365092254	-0.0076593317174342	-0.2262295610194124	0.0112051666994447	
+0.6110000000000000	0.0752145226809866	0.0276350028108912	9.7785775360268516	0.3901536950010787	-0.1170132700613005	0.3113813074375824	
+0.6120000000000000	0.0527411049897156	0.0387887650390134	9.7866244809153962	0.0214276474473111	-0.2672236701466128	0.1819248225080028	
+0.6130000000000000	0.0634433836191168	0.0162708358718428	9.7864132168963280	-0.1250998123911372	0.0476109174742481	0.0576556021995745	
+0.6140000000000000	0.0784410588952586	0.0369929041996238	9.8109653558253509	0.0088319875185316	0.1709932311577212	0.1132678518778366	
+0.6150000000000000	0.0368376251396325	0.0335536167481140	9.7895208637172288	-0.2072399042203619	0.2317614278926151	-0.1940997003079503	
+0.6160000000000000	0.0735033264066473	0.0406430082326164	9.7814556814706410	-0.0048541494051836	0.1595776251041250	-0.0966008839828581	
+0.6170000000000000	0.0736574577288131	0.0226844063867761	9.7970180509625635	-0.0399943026260186	-0.1282983004608242	0.2715351697992361	
+0.6180000000000000	0.0608149503846469	0.0241379159053057	9.8055073094085472	0.0366217179180202	0.3411591987928542	0.3796124814570648	
+0.6190000000000000	0.0742289435349299	0.0222835542569990	9.7976871301863468	0.0294295441012174	-0.0911482402033948	-0.2076020045605102	
+0.6200000000000000	0.0592365831426027	0.0232641354599622	9.7838546840587721	0.2839378256726633	0.0101590101089662	0.2031850663217447	
+0.6210000000000000	0.0726228501085937	0.0155435176250432	9.7959877528825601	0.1212988509075121	-0.2148650127215815	0.1079044389655821	
+0.6220000000000000	0.0483913818216243	0.0389738601688608	9.7787918070798252	0.0271656601378977	-0.0657474631526064	0.2002084048007558	
+0.6230000000000000	0.0484623206371175	0.0286035581721743	9.8133058369760544	0.3907943677313814	0.1499791023640259	-0.0127766754272011	
+0.6240000000000000	0.0636186485192970	0.0214647305477419	9.8096056797950144	0.2136750142190734	0.0695672976786928	0.0279909899622915	
+0.6250000000000000	0.0670457808928733	0.0261713169961796	9.8048913120224164	-0.1022055138151314	-0.0348301460955941	-0.0782897816045931	
+0.6260000000000000	0.0460024257735514	0.0309145872244181	9.8075128162034932	0.0809377885617809	-0.1671909867113275	-0.0458162598945000	
+0.6270000000000000	0.0620731633511917	0.0200461587242240	9.8103511113178232	0.0621267359552965	0.1129781396777216	-0.0553936889473921	
+0.6280000000000000	0.0792419329675071	0.0111048391969597	9.7781638369541906	0.2049470890917249	0.0019934895741887	0.1311097444583716	
+0.6290000000000000	0.0535170981078604	0.0043205457276278	9.7878596719749495	0.4667036444156878	-0.0003220490174614	-0.0080106393330844	
+0.6300000000000000	0.0437696091341110	0.0188473173446784	9.7835209127533602	0.2591592707079816	-0.1350001243325620	-0.0073271494276288	
+0.6310000000000000	0.0542310251382103	0.0391840187135258	9.7963956139657018	-0.0384408398883533	0.1023079117581265	-0.0829144033690642	
+0.6320000000000000	0.0668624248993201	0.0260477161886156	9.7810705175757189	0.1364368910181241	-0.1295214420574370	-0.2306656317464614	
+0.6330000000000000	0.0721389798434419	0.0184637144359971	9.7736961890805922	0.3704548495886315	0.0159218026211245	0.0526775669592180	
+0.6340000000000000	0.0732338235641639	0.0509277215921927	9.7942212478190580	0.0129275753650285	-0.1112072496682559	0.0145564248706282	
+0.6350000000000000	0.0599786203701690	0.0453207477921877	9.7949348811591719	0.0431517398484521	-0.3771669169406925	0.4250989503874056	
+0.6360000000000000	0.0507981129938811	0.0244074936619127	9.7952114549958438	-0.0979260728246042	-0.0518736918189822	-0.1705614824111000	
+0.6370000000000000	0.0745664297015689	0.0265362566020017	9.8194000882146337	0.0727722515636083	-0.1645923767822614	0.0578517789141097	
+0.6380000000000000	0.0370929420011347	0.0082821298264454	9.7873227773493934	0.0336925781800331	-0.1785369731772252	0.1416455741040791	
+0.6390000000000000	0.0579559488315083	0.0321507643520648	9.7831046481870132	0.0396032387215371	-0.2741528329046682	0.3530601314579265	
+0.6400000000000000	0.0608179823123776	0.0478661322435822	9.7755087953060880	0.0287102165462612	0.1209430618251666	0.2719130720947835	
+0.6410000000000000	0.0518319558718670	0.0235919347214969	9.8147272984848843	0.0807838755083086	0.0762144122416178	0.2020674343145437	
+0.6420000000000000	0.0688109949953322	0.0236424799122311	9.7889444236936942	-0.1142103491761809	-0.0859847327687664	0.1286747480718617	
+0.6430000000000000	0.0631446694429526	0.0269534828206530	9.7979403852494951	0.3589126006576498	-0.1061245666986469	0.1084142358513120	
+0.6440000000000000	0.0775139801021300	0.0303302979151425	9.8192084323186926	0.0349459835643463	-0.0929756565785493	0.0190737758151375	
+0.6450000000000000	0.0560649612479992	0.0304980422690634	9.8094278309621448	0.2392429390254276	-0.0034277563293587	0.0452814197234356	
+0.6460000000000000	0.0664762889053066	0.0227704725924076	9.7891826052924173	-0.0139881185406833	-0.0724206319199457	0.3882608026866574	
+0.6470000000000000	0.0658738576404156	0.0161524849259339	9.8156916223158781	0.1222375563633429	0.2216206165801994	0.0557946104792464	
+0.6480000000000000	0.0629137751395512	0.0543957082710428	9.8099476549179840	0.1580217870843635	0.0694372687046737	0.1496924801734050	
+0.6490000000000000	0.0570967270308686	0.0288707477826573	9.8035244340235153	0.0924423506439396	0.0711385311680447	0.0120926178094284	
+0.6500000000000000	0.0630446278860855	0.0290568458072286	9.8000702739515031	-0.2499648667491324	0.0593938482599989	0.0541205471155007	
+0.6510000000000000	0.0669531272093908	0.0205304154473757	9.7980543430556271	-0.0711512523109620	-0.1983536854086823	-0.0973367712656117	
+0.6520000000000000	0.0609570911070699	0.0198870298648283	9.8049248508155262	-0.0631772712014761	0.2959505280112668	0.3687232366993267	
+0.6530000000000000	0.0518951793792274	0.0300230775467862	9.8064157112170367	0.1904557689116954	0.1570565077423720	0.0715113634966898	
+0.6540000000000000	0.0517073238693384	0.0428736335049369	9.7975050650478792	0.1018945881899415	-0.3093159797009101	-0.0473024586880183	
+0.6550000000000000	0.0601381620902674	0.0284955535551984	9.8024842389157314	-0.0294750916727989	0.0283706634092738	-0.0475757143857955	
+0.6560000000000000	0.0623053174377002	0.0152520804036887	9.8104261875257706	0.1421042915179720	-0.0590168640037833	0.3149224072977311	
+0.6570000000000000	0.0672736113487200	0.0145833173545471	9.7951680260170413	0.1153203878064859	-0.2637510264049645	0.0032135987415681	
+0.6580000000000000	0.0750582777147022	0.0191031843917741	9.8089225745396469	0.2288352375729708	-0.1433376016520747	-0.3051676226244845	
+0.6590000000000000	0.0666180190617376	0.0045642029543514	9.7911628330829767	0.0907440184107695	-0.0227076823468890	0.3208308448931229	
+0.6600000000000000	0.0611625700422025	0.0198898747043101	9.7890089439662997	-0.1365025357869872	-0.2155709027622900	-0.0001862263776708	
+0.6610000000000000	0.0385000913356983	0.0290306694336341	9.8091805236832954	0.1859516798634348	-0.3559724828111950	0.2705470929190362	
+0.6620000000000000	0.0659305495710876	0.0299251258279960	9.7703791040971506	-0.0544346848029027	-0.0041897676946005	0.0631467749025490	
+0.6630000000000000	0.0678891763968912	0.0298608293965816	9.7976231244514214	-0.0453510739137178	0.0919000168391983	0.2615130265590040	
+0.6640000000000000	0.0468602633822726	0.0046066601039950	9.8138324704980811	0.2822025474240209	0.1413972755754207	0.0110385911429702	
+0.6650000000000000	0.0421892556197329	-0.0041566270426444	9.8001748359041709	0.0330059603798233	-0.0595617200013980	0.0627169672721443	
+0.6660000000000000	0.0688154779336380	0.0237256502497664	9.7820198172813360	0.0259493511724701	-0.1316783087170302	0.1228902341862939	
+0.6670000000000000	0.0548212944750870	-0.0051999596802149	9.7916468915786350	0.2803194422421877	-0.0241929143541903	0.2155686175960844	
+0.6680000000000000	0.0564020591867529	0.0141228142162017	9.8265875479654046	0.0883383412726317	-0.0498705080620965	-0.0472886289156112	
+0.6690000000000000	0.0503733035165537	0.0205703357434800	9.7730634578015572	0.0564726377582192	-0.1817923380652961	0.0794287208110189	
+0.6700000000000000	0.0542469304799471	0.0068253246094007	9.7935957195157251	-0.1309571707924806	0.0185060305456450	0.0456967149370803	
+0.6710000000000000	0.0398993566516795	0.0224816345583479	9.7879675190705253	0.2206036192950853	0.3403651215341770	0.0288148009395443	
+0.6720000000000000	0.0511580847850358	0.0135143819009899	9.8188560868110919	-0.0432006921938559	-0.1092923262159646	0.1948693594971138	
+0.6730000000000000	0.0703639255706178	0.0313441063462650	9.7844903871918163	0.0145970269002954	0.1508566102485646	0.3224112396741404	
+0.6740000000000000	0.0446123960093767	0.0248938602105828	9.7933054492520970	-0.0221893050026121	-0.0574335313248428	0.1497694217762539	
+0.6750000000000000	0.0584181527829354	0.0326389530739524	9.7975574089795359	0.1847829826101333	-0.0146919652066919	0.2577996526846079	
+0.6760000000000000	0.0603240828948930	0.0455430616515480	9.7811294760339127	-0.1425001599698161	-0.3086775636041857	-0.0505761111567371	
+0.6770000000000000	0.0440267147512799	0.0256959558324928	9.7884346996265510	0.0622174283273771	-0.1408156164013977	0.2347636291108858	
+0.6780000000000000	0.0461773167414935	0.0060978470994216	9.8034021864645506	-0.1293220394823512	-0.1763767087728936	0.2944661401081038	
+0.6790000000000000	0.0598698618343457	0.0214526662210433	9.7858455972223268	0.0582391580401915	-0.0959049456746064	0.1051457630414915	
+0.6800000000000000	0.0448507323071214	0.0345786126311862	9.8000689574074666	-0.0704923173924203	0.1352531429247291	-0.0332276166051125	
+0.6810000000000000	0.0670663274502132	0.0250979340491625	9.8027322893893380	-0.1152385336473197	-0.0571088883118650	-0.0339058002895091	
+0.6820000000000001	0.0665352459258569	0.0378916417944843	9.8016517246888064	-0.0539545915020719	0.1297346515718805	-0.2529387960065640	
+0.6830000000000001	0.0620932061238078	0.0566408953891661	9.7886533657303278	0.3597030947524613	-0.0425550786550766	0.1575497441997860	
+0.6840000000000001	0.0539738976313442	0.0018810281166568	9.8232276982960087	0.1344553349472009	-0.0145420470319400	0.2198341881453166	
+0.6850000000000001	0.0408678373002627	0.0399798514961955	9.7837563321467265	0.3631934232473084	0.0674887978537634	-0.0001541241983557	
+0.6860000000000001	0.0923379415110466	0.0003947001888058	9.7740189079780304	0.1242083962370750	-0.0463333582906945	0.2886946153430457	
+0.6870000000000001	0.0369236071352905	0.0204698814933224	9.7945105786525932	-0.0077746772377414	-0.0975615549855687	0.0057059603483929	
+0.6880000000000001	0.0329595084648676	0.0199306492705466	9.7840459339916599	0.1408689815972143	-0.1930594918358362	0.1415716412408616	
+0.6890000000000001	0.0587547663971439	0.0440900785811844	9.7926220901319887	-0.0457144155959479	-0.0593585826925665	0.1121363389228998	
+0.6900000000000001	0.0619863267806072	0.0170010922671653	9.8028084475034536	-0.0589656553725364	0.0242218120206591	0.1325260390111819	
+0.6910000000000001	0.0598172663153407	0.0243542199564243	9.8014761235031411	0.4188430506242036	0.1697000500815750	-0.2773169006112521	
+0.6920000000000001	0.0856185207140799	0.0027746750503611	9.8032998240147258	0.0917811033069378	0.2460921265230782	0.0167611441815594	
+0.6930000000000001	0.0517677139042428	0.0421485848284158	9.8054070375534010	-0.0424837213303578	-0.0691739537294982	-0.0237561698456002	
+0.6940000000000001	0.0686730235308848	0.0307041491386975	9.8107805036076297	0.1793691039680194	-0.0710156904449719	0.2202199957212176	
+0.6950000000000001	0.0626636609165011	0.0199655621327957	9.7946088325591560	0.1247637325048419	0.0295670656027010	-0.1475038118825663	
+0.6960000000000001	0.0468341151802859	0.0060088574508777	9.7880142657812108	0.0707122692979010	-0.1669091960604016	0.1020053064978266	
+0.6970000000000001	0.0564705464249355	0.0373325886381753	9.8015334917331440	0.2870405018373363	0.0832355256498876	0.3222749278493900	
+0.6980000000000001	0.0629241107677576	0.0257055411694432	9.7973590897596843	0.0908451893354940	-0.0356071684797696	-0.0422054906421496	
+0.6990000000000001	0.0834161855909215	0.0290554237524839	9.8069337800095600	-0.1762960642354715	-0.1006935686558047	0.0719238769864315	
+0.7000000000000001	0.0508104776990825	0.0422758332767949	9.7872026087842716	0.2216192736811772	-0.0833124102551052	0.1735742779909918	
+0.7010000000000001	0.0753838464835065	0.0488848645007557	9.7947263392239687	0.0787655775020281	0.1631835041232280	0.1560939100085827	
+0.7020000000000001	0.0566647392807064	0.0398257394889128	9.8088251781486377	0.1895368722042702	-0.2345280181521321	0.3698837276360829	
+0.7030000000000001	0.0594727629782034	0.0052971710710394	9.7812546549088211	-0.2316100485460513	-0.0321868466882247	0.1186291818025607	
+0.7040000000000000	0.0642478899508732	0.0039555383482444	9.8124191553764177	0.1829700914389765	-0.0534000206144444	-0.2269999922633752	
+0.7050000000000000	0.0572583924491854	0.0191360058147087	9.8061896646953173	0.1088620803883434	-0.2977093284829296	-0.2275304979588343	
+0.7060000000000000	0.0533794749219344	0.0399456209097491	9.8154336369047677	-0.0510884406545159	0.2400312196121163	0.1148878594879027	
+0.7070000000000000	0.0699900067738543	0.0174659597567815	9.7849568206013906	0.1908347060317527	0.2998870653990657	0.1207343505946956	
+0.7080000000000000	0.0564773359146614	0.0340911138293493	9.7929728511087735	0.0975660902112413	-0.3798981964358001	0.1408728561507767	
+0.7090000000000000	0.0597606403060716	0.0171066033949916	9.7973179087185240	0.0563526896792798	-0.0764040865467062	0.2163397189198161	
+0.7100000000000000	0.0595865809476745	0.0349123910257138	9.7753437479427134	0.0692025862344989	-0.0804179960301557	0.1877867094695754	
+0.7110000000000000	0.0477477640868985	0.0318421155242070	9.8123847485778839	-0.0791245175814794	0.0236728519582133	0.1336305497314103	
+0.7120000000000000	0.0680354500039796	0.0184159673841697	9.8030101297584480	0.1107332178745645	0.1999813714048652	0.2779352453721374	
+0.7130000000000000	0.0419246003688241	0.0333098043295292	9.8131836225206719	0.0337920979539405	-0.0521184272099773	0.5560156863068645	
+0.7140000000000000	0.0615661222859906	0.0280250239735706	9.8072267108726603	0.0408317458732390	0.2461564198525232	0.1058400390107220	
+0.7150000000000000	0.0524995517341459	0.0112611631250411	9.7925152493976739	0.0724889860106066	-0.2779402092123873	0.0660158999291636	
+0.7160000000000000	0.0831945020250941	0.0303245772781688	9.7910366001239435	0.2464802136797347	-0.0885900440336863	0.0825417179753768	
+0.7170000000000000	0.0902642750857458	0.0268627525280877	9.7952415432684425	0.1422370281005269	-0.0508341907519627	0.1590976789549776	
+0.7180000000000000	0.0637349843840621	0.0364676567909959	9.7715952271463742	0.2764995566312541	-0.0345587160962600	0.1129874576096039	
+0.7190000000000000	0.0727063877712218	0.0188804982379522	9.7883317487892292	0.0422099617213935	-0.0032624273031518	0.1064160620691831	
+0.7200000000000000	0.0679259893044752	0.0288982745599236	9.7795564412774869	-0.0371710830420542	0.0952690057221598	-0.1719583942109134	
+0.7210000000000000	0.0563981127426404	0.0207810398448205	9.7992283165999634	0.0558760121369375	-0.3519141404581491	0.2472986393680092	
+0.7220000000000000	0.0546417464965331	0.0294946639668051	9.8111788339281016	-0.1284107460805445	-0.0616076805797472	0.1369519894326670	
+0.7230000000000000	0.0632966935492766	0.0281746662664737	9.8025539889275510	0.2978497636892625	-0.1349987477542973	-0.0700713730518091	
+0.7240000000000000	0.0669742706017948	0.0071514016790171	9.7953388279861429	-0.2531091777126492	-0.0194318303078767	0.1837666736138187	
+0.7250000000000000	0.0791689086496159	0.0206062538795066	9.8137319772284908	0.1879562449541036	0.2645624311138282	0.0545751895007619	
+0.7260000000000000	0.0494662535930272	0.0219885721542660	9.8093155912957659	0.2698067707211963	0.3863753471823832	-0.1363074482228079	
+0.7270000000000000	0.0709196933459913	0.0374445355867097	9.7891325023595073	0.0287021462518342	0.0038516584012112	-0.0973129964612032	
+0.7280000000000000	0.0674360404742450	0.0248787094619529	9.7917844973104291	-0.1499695427237431	-0.3550775108807828	-0.0180337434381552	
+0.7290000000000000	0.0748262259497787	0.0126218226082483	9.8061463005843823	0.0499022008156793	-0.0301230894989968	-0.0245216900710501	
+0.7300000000000000	0.0539469202155515	0.0086513787500391	9.8092850103546354	0.1085412752014175	-0.0252562118492411	-0.0588097449900804	
+0.7310000000000000	0.0681906197444979	0.0298099862169044	9.7987584096608540	-0.1476172444070646	-0.0276045484012622	0.3553626137330902	
+0.7320000000000000	0.0625895627611970	0.0295618547744689	9.7936251105148528	-0.0086606085427026	-0.0688958952662721	0.1843939291417088	
+0.7330000000000000	0.0440455519988989	0.0200656926277880	9.8153054688518733	0.0144585413795079	0.1935500767679959	0.1420866634743485	
+0.7340000000000000	0.0468828654548711	0.0144856451685941	9.7968012914956617	-0.3356765811736223	0.1706826279689454	-0.0084931423551346	
+0.7350000000000000	0.0668377929264324	0.0377697843735394	9.8108516277764224	0.3538448225806784	-0.1292150052507499	-0.0306713341362019	
+0.7360000000000000	0.0668673346761791	0.0318966745361026	9.8183270673805829	-0.0710574441632534	0.0520677956754042	0.0432911090396406	
+0.7370000000000000	0.0756360510439966	0.0210807639576969	9.7800715260523905	0.0247039840051815	-0.0611172024316188	0.1459802688290646	
+0.7380000000000000	0.0565628460124863	0.0094441871265629	9.8206269000816686	0.2296259646571145	-0.1849659800146703	0.0289307997451190	
+0.7390000000000000	0.0667164005467593	0.0259317837052321	9.7824276855066792	0.1205845921205497	-0.1044137697145961	0.0765835850532015	
+0.7400000000000000	0.0593880161081746	0.0245375484104188	9.7974670102739214	-0.2735059746439035	0.1083868188224828	-0.0698256163614554	
+0.7410000000000000	0.0379588407675705	0.0149875300997924	9.7940983197583780	0.2169067785855844	-0.1453079942836337	0.1153012627289337	
+0.7420000000000000	0.0660988807487033	0.0399079570549345	9.7933763346657035	0.0409679843382468	0.0239895556619851	0.1639505796539712	
+0.7430000000000000	0.0687393645345554	0.0269396357903334	9.7858624549655158	0.3050182299034307	0.0747096313384828	0.0613744994692725	
+0.7440000000000000	0.0449674186746939	0.0070856077038458	9.7987166558222132	0.0885455126941604	0.0233928703214409	0.1500001003790487	
+0.7450000000000000	0.0787700851398266	0.0251186619518751	9.7816830834633830	0.1633261495621092	0.0361161772782032	0.2086717008996521	
+0.7460000000000000	0.0445137332395826	0.0368330905873786	9.7767365698253208	-0.0356931891277778	-0.0661611860654973	0.1745805257904470	
+0.7470000000000000	0.0694901991759505	0.0262640461550933	9.8023397006049642	-0.2917536088994990	-0.0621311479477362	0.0716650886108160	
+0.7480000000000000	0.0501548735665223	0.0361933230054671	9.8078359653223721	-0.0170809945755803	-0.0204998847689406	0.1099296739683052	
+0.7490000000000000	0.0552730868641725	0.0272089141469869	9.7996709806813822	0.1032770548294416	-0.1471506247604306	0.0561314773248601	
+0.7500000000000000	0.0393791675509319	0.0264133048169992	9.7915608527659703	0.2711700404185120	0.1517039806611042	0.0462415910167809	
+0.7510000000000000	0.0668959566316523	0.0192972773807345	9.7868454846781319	-0.2375173547640562	-0.0036876722681122	-0.1104670974290905	
+0.7520000000000000	0.0690171545434077	0.0426362724946714	9.8144297842250019	0.1162255003660007	-0.0561979919790439	0.1128498124131957	
+0.7530000000000000	0.0373631179188724	0.0144046506741389	9.7950002204124136	-0.0916539103193455	-0.0323772069318442	-0.0338207010128027	
+0.7540000000000000	0.0571446943100097	0.0375211683686699	9.7958644183435322	-0.1253114532250212	0.0008855663080836	0.1371255637472779	
+0.7550000000000000	0.0669084353456777	0.0191935382256163	9.8025117010480276	0.2022232714149181	0.0862412873028116	-0.0706086617898212	
+0.7560000000000000	0.0383452350956230	0.0215590181076613	9.8202179276525055	0.0642098834330434	0.0956857673496256	0.0955701856982530	
+0.7570000000000000	0.0648003815539238	0.0087336744096721	9.8123461619964480	-0.0797382567530507	0.0046156093834906	0.1500083932730014	
+0.7580000000000000	0.0734720838900897	0.0366306778446076	9.7891858580842257	-0.0144974923915814	0.2252839757885320	0.0685084582696372	
+0.7590000000000000	0.0310605493676195	0.0243395568693630	9.7977176673951174	-0.1164655118421578	-0.2545109329988562	0.1310397844554614	
+0.7600000000000000	0.0603388121357370	0.0076098386272548	9.8040989140056922	0.2255515834933773	-0.0739789760430927	-0.1142746961282231	
+0.7610000000000000	0.0587010580700005	0.0317260721129674	9.7962074842094147	-0.1816496780557327	-0.1763036914153957	0.1272153255587893	
+0.7620000000000000	0.0578056693150320	0.0265308208411885	9.7919408998114292	-0.0140690584763612	0.1382186317302658	0.1633395667080283	
+0.7630000000000000	0.0616056209402052	0.0059558235229611	9.7844202675242737	-0.2170444843548056	0.0934609257619841	0.0497823823975226	
+0.7640000000000000	0.0421855529504147	0.0298694143180147	9.8259666153804233	0.2692925885564377	0.3687284102443842	-0.0204002743540140	
+0.7650000000000000	0.0700182443729969	0.0129627322912091	9.8095829380801778	0.0889237443985518	0.1089508427703947	0.0682099205032538	
+0.7660000000000000	0.0691781190298656	0.0243104038182221	9.7905100561717102	-0.0002934851759809	-0.1594289143055035	0.1296178801606900	
+0.7670000000000000	0.0660488983404220	0.0407462622994355	9.8138459724107960	0.0538660931099693	-0.1144151536402629	0.3716533725238427	
+0.7680000000000000	0.0776294436089202	0.0092656820321859	9.7789232317434003	0.3300066968360610	-0.3061837334128539	0.1074320627679881	
+0.7690000000000000	0.0853211866888899	0.0227615203197656	9.7920502295272343	0.0875128271738384	0.1620131200749829	0.1280520736457127	
+0.7700000000000000	0.0716061705060287	0.0247889828362478	9.7769250534747432	0.1351336407476658	0.0187530078304225	0.0747713128784505	
+0.7710000000000000	0.0618065350066204	0.0312685597082032	9.8093751559400069	0.0405298863968440	-0.2393607862920427	-0.0469820555006328	
+0.7720000000000000	0.0505233709396337	0.0145666980444011	9.7952242609895457	-0.0087555272795157	-0.1179158375899229	0.0646809510938655	
+0.7730000000000000	0.0630798152297882	0.0414561874192166	9.7900260352737742	-0.0294463077406304	-0.1217424255199171	-0.0061309134598327	
+0.7740000000000000	0.0774047019827189	0.0523707256321344	9.7784926314028873	0.3479816062605878	0.0269507085720551	0.1446794370745814	
+0.7750000000000000	0.0620949160906306	0.0176501884101777	9.8060357736381185	0.1380224613968679	-0.2219369898680474	-0.2569422584037758	
+0.7760000000000000	0.0645469620159226	0.0366338567175962	9.8069457450915341	-0.0175716307342796	-0.0121578701574327	-0.0775642291393929	
+0.7770000000000000	0.0510984485529562	0.0037712682161539	9.7904175465314491	0.1242037263304205	0.1035656549474550	-0.0654908455415575	
+0.7780000000000000	0.0593610657268394	0.0229855392199056	9.7934585471153000	0.0301557292572280	-0.1451261816603847	0.2003299946701983	
+0.7790000000000000	0.0764465177521462	0.0103896495319118	9.8051616002436646	-0.1544676273368665	0.2059145546736630	0.0053349030765110	
+0.7800000000000000	0.0434145857790680	0.0125652851700617	9.8036371961360196	-0.0034980339243148	0.0352659920552496	-0.1934149766171809	
+0.7810000000000000	0.0639333330738293	0.0246337758839972	9.7714567521555349	-0.0108137048854422	0.0059554105540939	0.3017535672547991	
+0.7820000000000000	0.0382468297058631	0.0135829972811450	9.7788686078066629	0.0849813427890202	-0.1295186969859305	-0.0459090877618166	
+0.7830000000000000	0.0669100133440107	0.0361030445144846	9.8005149213522387	0.0366409512479580	-0.0613669551999884	0.1404839672466584	
+0.7840000000000000	0.0507038282887379	0.0458515923958204	9.7812813576504745	0.2336907210737580	0.1207731905940605	0.1195193132881856	
+0.7850000000000000	0.0510816233223371	0.0025576100749861	9.8078936730049158	0.0417598093636815	0.0618842318958223	0.4381833749431595	
+0.7860000000000000	0.0665336795065937	0.0321984068990937	9.7896070822794190	0.0482411352982481	-0.0271635065879375	0.0220789650366251	
+0.7870000000000000	0.0540210648338363	0.0235128239598073	9.7808112487631611	0.1857015678014154	-0.1412464232736227	-0.0985174308985437	
+0.7880000000000000	0.0514613377414678	0.0156654411157627	9.8054519250895389	0.0344039347146546	-0.1482097513276549	0.0712435684919979	
+0.7890000000000000	0.0830219941342958	0.0269763371493151	9.7809986350800600	0.4482184730484374	0.0241796945828177	0.2142931975404962	
+0.7900000000000000	0.0633022922687291	0.0377305849086371	9.7856955595833703	-0.0428130210060356	0.0724245232746794	-0.0772320847704926	
+0.7910000000000000	0.0541125671825978	0.0174540644676343	9.8289670820339445	0.2483269057161820	-0.0724387378385375	0.1603270743732690	
+0.7920000000000000	0.0466967107632495	0.0223078468853178	9.8050505184838759	0.0048868013105345	-0.0794056646427850	-0.0851233930936035	
+0.7930000000000000	0.0751229973678125	0.0320511188593208	9.7884908079552009	0.0089621952122529	-0.1365927898739999	-0.0320515276541856	
+0.7940000000000000	0.0511603123225892	0.0258808762053318	9.8036273200256865	0.1645016259509530	-0.0924521804506418	0.0823904151844741	
+0.7950000000000000	0.0589566899156524	0.0183708469796756	9.8038801312705086	-0.2625666760348135	-0.0731072000419201	0.2675618493213767	
+0.7960000000000000	0.0723685527159994	0.0330484339693827	9.7982851164019298	0.2105259206144055	0.2121144366666393	0.2186492298971592	
+0.7970000000000000	0.0795076639802731	0.0260890749229543	9.7977692304667325	0.2224608637591471	-0.1754373272901689	-0.2808624206690907	
+0.7980000000000000	0.0458371969972283	0.0269699507563335	9.7874348594121869	0.0072515223756023	0.0414661716247485	0.3824321257338569	
+0.7990000000000000	0.0649966186737745	0.0257012380248595	9.8123199063922577	0.0453191835801652	-0.0207387897611109	0.2482955399721662	
+0.8000000000000000	0.0552086360551595	0.0320232324719085	9.7899488609732384	0.2458888214685054	-0.1676579302249089	-0.0396028522815875	
+0.8010000000000000	0.0700940701819240	0.0285998294411224	9.8208729515808404	-0.1264453693208676	-0.0478321160895227	0.1288925028283846	
+0.8020000000000000	0.0564169252456776	0.0240040699511318	9.7992427442986081	-0.1092515598689138	0.0497682052644923	0.1930115435671552	
+0.8030000000000000	0.0720932733778913	0.0440353741111836	9.8029303000118126	0.0526550768794612	0.0161219385643568	0.2427362210669265	
+0.8040000000000000	0.0527772223010547	0.0163763827482256	9.8102259825264344	-0.0287788002206204	0.0278849860079818	-0.0078327832992523	
+0.8050000000000000	0.0381360854628838	0.0337007010759554	9.7998844069016808	0.2298941194630183	-0.1328852486609409	-0.1309431517494509	
+0.8060000000000000	0.0695949841711219	0.0365224514302694	9.7893037180394771	-0.0416392219162310	0.0076189198071605	0.0245221335682515	
+0.8070000000000001	0.0636661403115892	0.0161467932449650	9.7885771875729333	0.1688198326698188	-0.2535169647806528	0.1893421405249083	
+0.8080000000000001	0.0359531029324364	0.0182762739614214	9.8189531673986128	0.0592836264911652	-0.1137589864429314	0.0425995108308717	
+0.8090000000000001	0.0520983123293325	-0.0043723386525265	9.7895404971866249	0.0273747722447178	-0.3187338391471428	-0.3332738458220484	
+0.8100000000000001	0.0531195422561854	0.0313039173757707	9.8050048914780703	0.2508486601613504	0.0449550998494823	-0.0933158273821916	
+0.8110000000000001	0.0732491031441876	0.0282407903171181	9.7986486910291930	0.0102949980576981	-0.0030602755401072	-0.0258823996403297	
+0.8120000000000001	0.0701658122209510	0.0612840690202487	9.8041006309018695	0.1211334734531219	-0.0196533774187637	0.1384382234619113	
+0.8130000000000001	0.0456923050176321	0.0291854671148099	9.7917175874432321	-0.0338053237274099	0.0536558771331706	0.0321261649577717	
+0.8140000000000001	0.0605992566995657	0.0361365687005634	9.8021227182989623	-0.0969080967416268	-0.2212722947701811	0.1190645828780844	
+0.8150000000000001	0.0450745966879839	0.0217190484533521	9.7997363858088917	0.2255864700825614	-0.0111945599304840	-0.0051220285872087	
+0.8160000000000001	0.0641964889474858	0.0299568638582214	9.7993408634389656	-0.0762823469133734	0.0638176482190862	0.1146032658526219	
+0.8170000000000001	0.0552156484541286	0.0420362399906512	9.8170317527741915	0.1258730520755992	0.0705711125385732	0.0609577354832373	
+0.8180000000000001	0.0709488295434751	0.0035201614763575	9.7935891726005835	0.0765457949371736	-0.2161376665868754	-0.1239689449103865	
+0.8190000000000001	0.0688382718318410	0.0214757910317400	9.7927668465047866	-0.0027075367298780	0.0329710891734053	-0.1602319027016644	
+0.8200000000000001	0.0537258090869605	0.0407250833938744	9.7866841068264350	0.1182585011869821	0.0165974107680146	-0.0573403156621850	
+0.8210000000000001	0.0494851259600247	0.0180258976925544	9.7917889872829456	0.2364000524991567	-0.0616047798913889	0.1800557330306959	
+0.8220000000000001	0.0427758246472302	0.0111982477228560	9.7980466858627526	0.0156232569556635	0.1600879836341105	-0.0585768689258100	
+0.8230000000000001	0.0598888556902874	0.0214210448615232	9.7752872686311569	0.1023774040270919	0.0830331393975574	0.1989745542554707	
+0.8240000000000001	0.0666963648492607	0.0430096303905472	9.7869724307067063	0.1526164740948783	0.1098261826241602	0.1690951782375068	
+0.8250000000000001	0.0588534719063082	0.0167096049194136	9.7910048015555411	0.0005882577988995	-0.0737994077553640	0.1587489637920887	
+0.8260000000000001	0.0595245106316398	0.0470404611856692	9.7938693866979207	0.0989333874358419	-0.0730892791127857	-0.0162861492539085	
+0.8270000000000001	0.0634562934230459	0.0207482907707400	9.7852711761086333	-0.1131460741572665	-0.0689327639034491	0.0604577365218622	
+0.8280000000000001	0.0410490023592629	0.0039227211583304	9.7818092215502723	-0.1944607365245451	0.0496562748648149	0.3598760354193271	
+0.8290000000000001	0.0696589687111989	0.0115716550949819	9.7936440974161219	0.0245413174124802	0.1099128094399108	-0.2350627900491442	
+0.8300000000000001	0.0544962199666243	0.0593750815595440	9.7899914265285606	-0.0142056600811608	-0.0791814776577652	0.0738168080897264	
+0.8310000000000001	0.0640501398293398	0.0077856174590311	9.7664498418683365	0.1728564532389699	0.1971299065780049	-0.0785482984243928	
+0.8320000000000001	0.0592021158602745	0.0342185723545127	9.8066937907002956	-0.0198892072063956	0.2188012874750422	-0.0492516083310584	
+0.8330000000000000	0.0839169567018146	0.0246778060160778	9.7938604338619530	0.1032146912292442	-0.1250017943878521	0.1375900027500697	
+0.8340000000000000	0.0663250959366423	0.0251433400493299	9.7847257577869851	-0.0295491699457318	-0.0132722906313999	0.0403918761877250	
+0.8350000000000000	0.0387704317901359	0.0217997978550147	9.7965468444007726	0.2766510279902078	-0.0051789852660625	0.0917001517825555	
+0.8360000000000000	0.0471598737604092	0.0357983865709108	9.8155248876510655	0.0326352650038939	-0.2210396187682689	-0.1206423996647221	
+0.8370000000000000	0.0693738043840494	0.0145756010039323	9.7866664102177108	-0.0598366240860027	-0.0463360181866527	0.2829082684223853	
+0.8380000000000000	0.0617595115267146	0.0335681699309830	9.8007620693889752	0.0137551326211787	0.1093364266235138	-0.0436874018504367	
+0.8390000000000000	0.0627372754323801	0.0539540504353517	9.8015775834247787	-0.0556259106289482	-0.1916069307292803	0.3344532142480657	
+0.8400000000000000	0.0444652418958196	0.0221847407937269	9.7770911937498166	0.3574622877931510	-0.0292707439991790	-0.0209093225175176	
+0.8410000000000000	0.0556391833888777	0.0250530413851649	9.8044870922059193	0.1670475494045986	0.1191130833914842	0.1751645046268818	
+0.8420000000000000	0.0620219542789028	0.0372316336567659	9.7978263277718014	0.1462505910674066	-0.1145330800633132	0.2217297547262372	
+0.8430000000000000	0.0815297992911403	0.0334184575654235	9.7934969178321847	0.0948633097818765	-0.2914038568599387	-0.0646175679025891	
+0.8440000000000000	0.0396520461589381	0.0123781160629861	9.7765686944768397	-0.1987764664751450	0.2065844701028862	-0.1036397068166994	
+0.8450000000000000	0.0754474116413218	0.0141979276189259	9.7950316498810537	0.2636763178126196	0.0220232901046150	0.3067852090319860	
+0.8460000000000000	0.0533288537679765	0.0066050370965408	9.8240090353886362	0.0315867538077776	0.2824669976081290	0.1213837333006163	
+0.8470000000000000	0.0619582081087069	0.0343627837799723	9.7893262399962264	0.0344237141316126	0.0607958091691475	0.2255280856055066	
+0.8480000000000000	0.0506913435031782	0.0292613089465159	9.7963687278759739	0.2463914811959415	-0.0486224906298911	0.1137807669708660	
+0.8490000000000000	0.0472663996477907	0.0231835824011865	9.7921951594039136	0.2823782219283758	0.2023993440466199	-0.1646195060597742	
+0.8500000000000000	0.0434642395299364	0.0035130378009975	9.7805865247533053	-0.1032526963052486	-0.1755844846855504	0.1386836993319224	
+0.8510000000000000	0.0576669024570954	0.0125981452893902	9.8048133823675201	0.1086674888419574	-0.0667548410922150	-0.1354001190617201	
+0.8520000000000000	0.0467104518489239	0.0302115861375735	9.7902473173546447	-0.2065354284270258	0.0093687121010348	0.1063168595058601	
+0.8530000000000000	0.0469813386531981	0.0375750693087824	9.7958562247024688	-0.1936949438923403	-0.1566440805262608	0.0721849692317236	
+0.8540000000000000	0.0579173006422532	0.0231222751155881	9.8227471537239506	0.1647422977134956	0.1657607784595798	-0.1392050467287181	
+0.8550000000000000	0.0579774214356113	0.0119238119888307	9.7832653497183024	-0.3110367445505554	-0.1443649632424351	0.0793018266988185	
+0.8560000000000000	0.0581614554488376	0.0096470923105086	9.7956810299771906	0.0841484284513757	0.0201500842531443	0.3436057190496010	
+0.8570000000000000	0.0418535117976725	0.0358300189489284	9.7987853368151061	0.1631972247084316	-0.0304721113259595	-0.0519917960847939	
+0.8580000000000000	0.0664047865247770	0.0199941507966981	9.8327482771754102	0.2771248502859322	0.1624503092681464	0.1652977712230181	
+0.8590000000000000	0.0561141792831375	0.0325744317881335	9.7912498898862914	0.0584870412276053	-0.1787807525152599	0.0337520298289474	
+0.8600000000000000	0.0709839166700084	0.0244782783613121	9.7967349042369190	0.1478224502651406	-0.1160257217850701	0.0306073623862156	
+0.8610000000000000	0.0806810337332983	0.0123365901079163	9.8002154589336161	-0.0306326804405203	-0.1782806402753183	0.0466592549890366	
+0.8620000000000000	0.0571823717376523	0.0135947920616390	9.7704186141085376	0.0908164758329683	0.0328076708715128	0.4332787896236088	
+0.8630000000000000	0.0649502019408006	0.0050050030907192	9.7994091903465126	0.0700554923491625	-0.0156513619234594	-0.0762631478158314	
+0.8640000000000000	0.0442978093681249	0.0299485328677561	9.7947105828624856	-0.0369445519925361	0.0750131472241339	0.0479493504123939	
+0.8650000000000000	0.0500874099348578	0.0172198851677785	9.8039309183874614	-0.0977318990154499	-0.4791497528997278	0.1054500760310393	
+0.8660000000000000	0.0619036488951726	0.0138337240341119	9.7998977007771018	0.0423013542911169	-0.0065844652106946	0.1824389144347128	
+0.8670000000000000	0.0641112729323163	0.0230719233615952	9.7833757924578961	-0.0087659320437947	0.0781411041474957	-0.0355404384202246	
+0.8680000000000000	0.0672132849535947	0.0046778571654164	9.7862786206687673	0.2428972508905133	-0.3781920302780177	0.0197573137328517	
+0.8690000000000000	0.0673656207885489	0.0416373648838731	9.8000726253278323	-0.0749900030124592	-0.1351733952247376	0.0838570753675736	
+0.8700000000000000	0.0660143102243893	0.0168147559399637	9.7968673758547506	0.0291962232173999	-0.0729948131981214	-0.1863119745993922	
+0.8710000000000000	0.0522891875400286	0.0392047506915496	9.7763200807917983	-0.2499339570287041	-0.0059638486655734	-0.0940824428688434	
+0.8720000000000000	0.0650363040168633	0.0217692805673195	9.7944346800789202	-0.1521040343308090	-0.1483323468796591	0.1946296372263984	
+0.8730000000000000	0.0629258796323235	0.0301153506522175	9.7982638602725682	0.1512380271815636	0.1654416860333730	-0.0088991789117158	
+0.8740000000000000	0.0613755401271628	0.0358266178280101	9.8025381951175063	0.2568862216859000	0.1626607039243609	-0.0997554935343983	
+0.8750000000000000	0.0811239930838778	0.0101714730655102	9.7958461784975750	0.0041245327889410	-0.0693403219646203	0.0810176411246026	
+0.8760000000000000	0.0668813173028423	0.0243248648223794	9.8142265860779467	-0.0640339999047903	-0.1096688495461803	0.1240146818459320	
+0.8770000000000000	0.0511772101704650	0.0261803667122226	9.7972548139945914	0.2127100087008457	-0.1939304755739384	-0.0353607287408411	
+0.8780000000000000	0.0571003760963101	0.0354555093022263	9.7871705631731896	0.0191192967376617	-0.0961712307408385	-0.1378395057329863	
+0.8790000000000000	0.0481125557141765	0.0428673467214590	9.8197032299295852	0.2805234634725760	-0.1324358300418887	0.0403849232227933	
+0.8800000000000000	0.0505650209368048	0.0106171360611652	9.7742808178366953	0.3578695738737261	-0.0340784246941527	-0.1748751605259931	
+0.8810000000000000	0.0433718621007795	0.0227088287159732	9.7985002172238573	0.0564724192637764	-0.2652733584363144	0.1372710184644066	
+0.8820000000000000	0.0749467077707111	0.0448060419699800	9.7742099944697145	0.2475945719777496	-0.2420183880492809	0.3361933377153587	
+0.8830000000000000	0.0586033510606126	0.0166116651865043	9.7920169467534581	0.0607937181440081	-0.0089337700813137	-0.0173429964779489	
+0.8840000000000000	0.0605915890967755	0.0248494112879087	9.7914628882457873	-0.0904210124895876	0.0570125187934204	-0.1190472262671681	
+0.8850000000000000	0.0774482912150921	0.0301085384192571	9.8093589020503025	0.1938099486141157	0.0318848876972066	0.1744184562468978	
+0.8860000000000000	0.0475444245305651	0.0154128787240182	9.7991155554143017	0.1052064250083307	0.1687339384526317	-0.1001355193286167	
+0.8870000000000000	0.0545640394145792	0.0395545982283990	9.7913161328580909	0.1527885960160981	-0.1603218619923703	0.0192692800782532	
+0.8880000000000000	0.0542916825944246	0.0353226949689402	9.7977821249331907	0.0196368511269165	0.1994123330129728	0.0773558289818855	
+0.8890000000000000	0.0589216134416526	0.0272403153629092	9.8210274701484064	0.1179760744327830	0.0334264075742520	-0.2242628114673528	
+0.8900000000000000	0.0509575148349137	0.0188957957838750	9.7935301463591102	-0.0622240036770469	0.1251168365128956	-0.1848303544168610	
+0.8910000000000000	0.0680642668581443	0.0204551765838168	9.7992481584417757	0.1455369333869453	-0.0116488218729682	0.1907568476726725	
+0.8920000000000000	0.0776785669575857	-0.0038368742210940	9.7837684906480078	0.0980439607236314	0.0306960405121929	0.0255123990860802	
+0.8930000000000000	0.0497295165949475	0.0203099049706017	9.8018671436477938	-0.0606592430465129	-0.1174654037199577	0.2550274900951952	
+0.8940000000000000	0.0663633038261853	0.0367910488033727	9.8028952337025128	-0.2071044655824125	0.1032433206157332	0.3856466914048752	
+0.8950000000000000	0.0675146607175601	0.0367218212266965	9.7908746487429017	-0.0761058329225120	-0.0489594558876599	0.2456030060063579	
+0.8960000000000000	0.0559681895031668	0.0211323003716009	9.8092439766861794	0.1950265435135044	-0.0475055345362829	-0.0421514861218383	
+0.8970000000000000	0.0501255369478217	0.0251602884241340	9.7934620412013160	0.4501520631200551	-0.0895759904833320	0.0470175457262877	
+0.8980000000000000	0.0626012302800381	0.0435589335791220	9.7889210888162150	-0.1107735904185100	-0.0957573437151945	0.0300991416170631	
+0.8990000000000000	0.0712324415343971	0.0259021052757356	9.7860100453920005	0.1302147250559438	-0.2633386059652218	0.2967219159894106	
+0.9000000000000000	0.0607366342348044	0.0078239002276880	9.7950936707115233	-0.0979279627600849	-0.0582146039242559	-0.0099389918883575	
+0.9010000000000000	0.0527374937058476	0.0217638911155444	9.8037495395743814	0.0420984681283850	-0.1764836710615874	0.0382574482721053	
+0.9020000000000000	0.0810449064392192	0.0314903875334999	9.8088126575356949	0.3069369960022945	0.0658872442492838	0.0231437701039045	
+0.9030000000000000	0.0566443649257472	0.0453162514075010	9.8077835686935728	-0.0194681770025391	-0.0142634113055513	0.0649201642839793	
+0.9040000000000000	0.0487985628245047	0.0511069877682442	9.7965385294141285	0.0381904595278826	-0.0329080052465235	-0.0655746806741936	
+0.9050000000000000	0.0493291629588869	0.0164782352750053	9.7943433925668000	0.3144690947363564	-0.0628535921963803	0.3189908760193930	
+0.9060000000000000	0.0604589267000425	0.0430594684796365	9.7857125783472423	0.1485803474068352	0.1087852474379321	0.1690865140022386	
+0.9070000000000000	0.0711373351199736	0.0164855118043053	9.7920006469300809	0.0224724022919532	-0.0141666367361155	0.3796418075848412	
+0.9080000000000000	0.0521681186052363	0.0302150225399261	9.8120181362538794	0.0478940608498056	-0.3079788765547802	0.1647845997547582	
+0.9090000000000000	0.0534850983462796	0.0392441757564973	9.8216640257859247	-0.1945455092608181	-0.3451016628412300	0.2089378137749659	
+0.9100000000000000	0.0452017124123817	0.0352508635464751	9.7729674864248821	0.0327317688457483	-0.0489393240395945	0.2695885029755065	
+0.9110000000000000	0.0633657755761970	0.0204987181847615	9.7964624716309920	-0.1410736363561679	0.0182737677507504	0.0654203058904238	
+0.9120000000000000	0.0447301076159877	0.0220578444866328	9.8065340336523406	0.0008412444229079	0.0964376284127683	-0.0771065034330675	
+0.9130000000000000	0.0830594289859252	0.0385848303642065	9.7945811528142759	0.0587803170087544	-0.0732649734282566	-0.0379460216540276	
+0.9140000000000000	0.0566641448465371	0.0175404534942399	9.8176682270605369	0.0909382868381797	-0.1901855910249931	-0.0327609922930501	
+0.9150000000000000	0.0528056839822518	0.0231665728354513	9.7813306457898328	0.1737375385275008	-0.2228008384919039	-0.0182643457495349	
+0.9160000000000000	0.0468322013705901	0.0295802452902232	9.7989381821449371	0.0169044544868955	-0.1113598330429014	0.1615083083572942	
+0.9170000000000000	0.0845871610900870	0.0034289279364865	9.7868075165341626	0.0696180986026282	0.1654518963515373	0.0759966681322041	
+0.9180000000000000	0.0660096778647775	0.0141031508163085	9.7892206394426573	0.2120710239278707	-0.2801340607353898	-0.0860317224356589	
+0.9190000000000000	0.0630387693483541	0.0168167801892922	9.7694750958560217	0.1590429509955749	-0.0515206717773338	-0.0385723786369495	
+0.9200000000000000	0.0699262435804303	0.0356986544354852	9.7845071337886136	-0.2964153711765629	0.0131486771022330	-0.0228408879995007	
+0.9210000000000000	0.0777713045826519	0.0273277683165994	9.8122814087056156	0.1134808116480341	0.0539780393056940	0.0189334126576816	
+0.9220000000000000	0.0766793741980000	0.0271137060121306	9.8101606946815618	-0.1158696706070520	-0.1071529157618153	0.2315663076289483	
+0.9230000000000000	0.0582138737246079	0.0330293105827173	9.8098019737407220	0.1119416207199404	-0.1457069695571816	-0.0424252642871303	
+0.9240000000000000	0.0552433468746620	0.0205523919294610	9.8121269893908014	0.1338152651004567	-0.0517891516032419	0.1162246383017582	
+0.9250000000000000	0.0352253555082526	0.0223712037721096	9.7963152357997707	0.1337424179319724	-0.2228651654163854	0.1574435113022090	
+0.9260000000000000	0.0581976349749286	0.0193326836831254	9.7931216693618488	-0.1091080343412480	-0.2707264440328335	-0.0620537244583519	
+0.9270000000000000	0.0602469723746697	0.0352413291727105	9.8096801908588542	-0.0482755120714454	-0.2682520381401228	0.1850123312092985	
+0.9280000000000000	0.0602591444954881	0.0197837697942955	9.7850047586850604	-0.0537714922193012	0.0471782631297893	0.0645389725263279	
+0.9290000000000000	0.0411285773981459	0.0436919273754428	9.7964207567720720	0.0863492602146246	0.1780285486575408	0.2972546081276811	
+0.9300000000000000	0.0706201575743294	0.0325141897144068	9.7933245709540220	0.2074158187693843	-0.1645323590040080	0.1210853557400483	
+0.9310000000000000	0.0337588633011220	0.0070628653163696	9.7901050114761787	-0.0189602423528932	-0.2338237320095568	0.1369305724664110	
+0.9320000000000001	0.0565504874806635	0.0235904910608044	9.7944544487115017	0.0197146931605364	0.0688853194511059	0.0555871515549702	
+0.9330000000000001	0.0576717333384493	0.0455990005110482	9.7809117547058992	0.2232279335707095	-0.1412625193860406	-0.0995607124029550	
+0.9340000000000001	0.0547474784726666	0.0320697474198180	9.8266710432323769	0.2349544943801496	0.0008860892659683	-0.0547168067758665	
+0.9350000000000001	0.0688000212473770	0.0221690712480473	9.7937580917284439	-0.0484053041614986	-0.0575041506837741	0.0183987188116140	
+0.9360000000000001	0.0588555875788635	0.0271670574489531	9.8016068463674806	-0.0498667361743892	0.1129565127641704	-0.0713373309923905	
+0.9370000000000001	0.0550194077440271	0.0144836913234016	9.8003877693214854	0.0292431951371034	-0.0058602597247885	0.1839396711808728	
+0.9380000000000001	0.0529527970466415	0.0191348119958416	9.7875180568909936	0.0661113552283982	-0.1864217526604958	0.1492380778410519	
+0.9390000000000001	0.0407023863455935	0.0360854699760043	9.7925534549897257	0.1196942186977763	-0.2288344556679553	0.0053436116022892	
+0.9400000000000001	0.0640529328108344	0.0154760077458423	9.7780010754490760	-0.0573692909410892	-0.2122963279995023	-0.0749225926323043	
+0.9410000000000001	0.0517151247293163	0.0152442355158302	9.7980133710118533	-0.0140669217252340	-0.0382824044076466	0.1885604251488015	
+0.9420000000000001	0.0764488326794673	0.0107736220164158	9.7853844602457940	-0.1877167151453412	-0.0743891568070139	0.2192708152205184	
+0.9430000000000001	0.0492163870968865	0.0329924359808251	9.7784056290298302	-0.0108212462207262	-0.3805667277604286	0.0410182098889289	
+0.9440000000000001	0.0555363200195327	0.0311391766857442	9.7901405736873741	0.2169271317463326	0.2147566272084293	-0.0935246406714888	
+0.9450000000000001	0.0472617446423145	0.0358412286956280	9.7680802632491464	0.1385744780897176	-0.0656407464107703	0.1819861043203126	
+0.9460000000000001	0.0614978863381147	0.0115273157523144	9.7965304554721300	0.0039870544643576	0.1781989291337128	0.0822925283464112	
+0.9470000000000001	0.0671920834605930	0.0307861205073404	9.8020939992191707	0.1495032137145432	0.0309983375955196	0.0820373886334586	
+0.9480000000000001	0.0445220922003170	0.0433282763536803	9.8109616225811838	-0.0585281912017654	0.1384992052850972	0.0005658433019458	
+0.9490000000000001	0.0517850383097312	0.0237903278583977	9.7956321954903043	-0.0603588223893786	-0.2420759494443976	-0.0185846035258840	
+0.9500000000000001	0.0523832119392986	0.0093381142658409	9.7938990228258316	0.0120343564738316	-0.1191639600415335	0.3908159449623500	
+0.9510000000000001	0.0755420774376374	0.0154602163878009	9.7958178479481290	0.1017222633843349	-0.0043427896181204	-0.1887357255289587	
+0.9520000000000001	0.0398264396717687	0.0366771947605735	9.7936060459038341	-0.0998016837629942	0.2423045561337055	-0.1623787254704621	
+0.9530000000000001	0.0482380675826993	0.0330327166865256	9.7832568171314911	0.0730296615351109	-0.1002230354154622	0.1906739823506780	
+0.9540000000000001	0.0767570765291146	0.0329636509501414	9.7999940911726107	-0.1248457504497140	-0.2510873429339634	0.1077260730661918	
+0.9550000000000001	0.0504056888577344	0.0275816950755026	9.7931597206966821	-0.2121163192688036	0.1568633283696660	0.0257126384725029	
+0.9560000000000001	0.0497624311596697	0.0161039113373049	9.7901797200795997	0.2270933427639154	0.0682577703740286	0.2246107520783826	
+0.9570000000000001	0.0528146113660647	0.0201263689554650	9.7725836724189694	-0.0176925608646573	-0.0435497749328879	0.0208516902188627	
+0.9580000000000001	0.0642133879672147	0.0200468938626068	9.8111455103468845	0.0202646708810609	0.0222371735685482	-0.1663626810092086	
+0.9590000000000001	0.0723235650366743	0.0201874861947216	9.7943795595572993	0.0160423280392262	-0.0313028546408753	0.1395774871483413	
+0.9600000000000000	0.0533757479012591	0.0212051263154374	9.7786903161198371	0.2305868714606244	-0.0754548113286984	-0.0371577101010924	
+0.9610000000000000	0.0962694587253109	0.0138445758314537	9.7927727614836702	0.0986720641218084	0.3696679965625835	0.1338328438809243	
+0.9620000000000000	0.0722089127733740	0.0185536060018884	9.8145881675581279	0.0326520889087261	0.1166235946720464	0.2470840294231811	
+0.9630000000000000	0.0680505558549960	0.0128980248085254	9.7756012085525708	0.0863106456835564	-0.1012159817405144	-0.0002979838611423	
+0.9640000000000000	0.0672948228311311	0.0138647249562356	9.8089712287395141	0.0979365846461838	-0.1894530926984171	0.2768060242738178	
+0.9650000000000000	0.0741435424509174	0.0521281420179934	9.7807515615590201	0.2078331776195885	-0.1200455477642656	0.2782279022294978	
+0.9660000000000000	0.0529855269403705	0.0375803059945390	9.7941324532063856	-0.0731600804118605	-0.0828542981320101	0.0917817661653577	
+0.9670000000000000	0.0724372242627425	0.0108126920190047	9.7831821408596511	-0.2433214755519749	0.1473663314314288	-0.2150213061704195	
+0.9680000000000000	0.0549391293008273	0.0309849668960978	9.8067694492542028	-0.0696060563348114	0.0296292720302581	0.0244298191382555	
+0.9690000000000000	0.0666168478603509	0.0171239675829955	9.8059846907474206	0.0495905545062947	-0.1080344065707161	-0.0037082729442881	
+0.9700000000000000	0.0690663249767630	0.0126690324266340	9.7969202214576452	-0.1258203119651096	-0.1118474757443243	0.0960134914725599	
+0.9710000000000000	0.0655519688145638	0.0302704628158175	9.7899596719934738	0.3044189169828866	-0.0718564958369545	0.0779279596714011	
+0.9720000000000000	0.0367133084984724	0.0145826706972077	9.8089172560627755	0.1682854026492859	-0.1594182772472983	0.0173558040972816	
+0.9730000000000000	0.0627664981629953	0.0241415072380827	9.7732771160682290	0.0954947578007291	-0.0290651630764324	0.4362220349418021	
+0.9740000000000000	0.0611732850861775	0.0347717203343000	9.7918269798367881	-0.0652925825355162	0.1109140669427277	0.1096337035180616	
+0.9750000000000000	0.0624701121489548	0.0090855050500021	9.8004116533280197	0.0433110435020908	0.1016208240482986	-0.1802644184424742	
+0.9760000000000000	0.0524532826077827	0.0199910243803977	9.8055091235571172	-0.0000973908266345	-0.1053163500980228	0.1334195560600191	
+0.9770000000000000	0.0615893748121510	0.0119431864617664	9.8063414997680418	-0.0315392198740494	0.2457504297193998	-0.1157513816706745	
+0.9780000000000000	0.0366202663061520	0.0345329782789787	9.8054069967854378	-0.3025635420648400	-0.0495114486587622	0.0131166803450132	
+0.9790000000000000	0.0905562261029541	0.0159728673029041	9.7790044830416729	0.0883510736381380	0.1123237205562325	0.0461646042426773	
+0.9800000000000000	0.0516981947962457	0.0235566976632814	9.7757567981615150	0.0180072869415224	-0.1110230867304558	0.1316058786208485	
+0.9810000000000000	0.0428014899916946	0.0208749885189675	9.7977075959488182	0.1537722467342416	0.1623947588141542	0.0750883589799694	
+0.9820000000000000	0.0555430869120493	0.0274434200597983	9.7985359029197081	0.0131090104639804	-0.0603181326541601	0.1504129145167373	
+0.9830000000000000	0.0648598690965622	0.0303526123101557	9.7652326540070309	0.1553401263237568	0.0113024501237498	0.1760775519464026	
+0.9840000000000000	0.0608251046260204	0.0224138483832068	9.7981655168919168	-0.0936924511710951	-0.0213703996397746	-0.0433884479711455	
+0.9850000000000000	0.0405927130066779	-0.0067035331272470	9.8040904512070792	0.1061377140072007	-0.1666634153065589	0.0634338659345171	
+0.9860000000000000	0.0700556353246634	0.0077825011438495	9.7935363931654607	0.3542855576945061	-0.1737901811926847	0.2249979131560559	
+0.9870000000000000	0.0678266471914920	0.0154006785108070	9.7984730070439383	0.0092303562549798	-0.1263893738498330	0.3293493607122303	
+0.9880000000000000	0.0622389532726621	0.0165555751552110	9.7921501444867598	0.0039015493187337	0.0615800414529998	0.1768755366361516	
+0.9890000000000000	0.0668657003626054	0.0271247311906557	9.7796447861462941	0.1729958574529945	-0.1140614065652434	0.0181632415389042	
+0.9900000000000000	0.0473296678368834	0.0319462672080824	9.8182787814937349	0.2304691775422933	0.2411539223985892	0.1363454235163386	
+0.9910000000000000	0.0683282974698966	0.0162917899250332	9.7956809803652565	0.3175983635856767	0.0827930330548884	-0.1457075156438864	
+0.9920000000000000	0.0508906179311668	0.0022014992304924	9.8101555114292580	-0.0248199058761492	-0.0740363700462338	-0.1884894142976021	
+0.9930000000000000	0.0449236317567641	0.0326088609042197	9.7950769066828567	0.1444942668364114	-0.0177744540855603	-0.1143995965329786	
+0.9940000000000000	0.0407336765722598	0.0274514990200115	9.7802441128133104	-0.1870904564954697	0.0533351429186066	0.0615956158918816	
+0.9950000000000000	0.0527886843598514	0.0328054591924622	9.7846757554248835	-0.0525719563551560	-0.2908432819901472	0.0289926175263745	
+0.9960000000000000	0.0678721398724036	0.0156662884216598	9.8040414760650823	0.3319523315188572	-0.1482418406454405	-0.0020502226895374	
+0.9970000000000000	0.0631426066630386	0.0281340540932085	9.8041048635041292	0.2348922675909503	-0.0441925509675959	-0.0185975857099244	
+0.9980000000000000	0.0643320945801676	0.0465131998210924	9.7968384692741122	-0.0557102441596075	-0.0254790839233696	-0.0097820476454250	
+0.9990000000000000	0.0681411107156319	0.0272500659323523	9.7966688307783389	0.2618802355702679	0.2400624094130902	-0.1115710822738551	
+1.0000000000000000	0.0463149544583531	0.0168993104768416	9.8171053793111849	0.0897037443870013	0.0008729602001614	0.1233224822588034	
+1.0010000000000001	0.0581041713855141	0.0366159238018915	9.8004123430013710	3.4681197301854385	0.1256339850651089	0.2237989872650765	
+1.0020000000000000	0.0633922793908438	0.0524089542496718	9.8075596059098782	3.1715536834562652	0.4741704663104015	0.0245405133504186	
+1.0030000000000001	0.0846511417382509	0.0913306312305914	9.8133584760219428	3.1384262435915660	-0.1342365507714055	-0.0246193517911147	
+1.0040000000000000	0.0521060315668563	0.1223238438584766	9.7916596337346267	3.3151050002939306	0.0311392807919618	0.2594414892415138	
+1.0050000000000001	0.0363585116631750	0.1282526712709458	9.8108343061046348	3.1093195636863986	-0.1074112189258866	0.0715118780420511	
+1.0060000000000000	0.0665159093441180	0.1753481619947382	9.8281259929154636	3.2030143569345602	0.0030763801755822	0.0652734305808915	
+1.0070000000000001	0.0880212849833821	0.2302282926576511	9.7968036247619334	3.0203029187743495	-0.0382163256166962	0.1293785833088572	
+1.0080000000000000	0.0550624623884406	0.2388938495272696	9.8173554297339773	3.0562220065403776	-0.0855923569557803	0.0662772590757448	
+1.0090000000000001	0.0717681216010024	0.2705543563816166	9.7958345102540925	3.0171357619224204	-0.1778760490446494	0.1416680694169457	
+1.0100000000000000	0.0662902517607802	0.3003759735122956	9.8083502174790507	3.1396172620043341	0.1163032605608792	0.0957955323358145	
+1.0110000000000001	0.0756270715636558	0.3440904387781367	9.8080212860282732	3.1469637640310824	-0.0920865218721948	0.1024898800188602	
+1.0120000000000000	0.0544599822610626	0.3762368811575583	9.7851851389048772	3.2385188034508641	-0.0222562328940361	0.1880482986173763	
+1.0130000000000001	0.0571777175059658	0.4001351778688790	9.7686548301886997	3.2740661091656529	-0.0535014572634713	-0.1094883337305004	
+1.0140000000000000	0.0615250906319520	0.4439576304909945	9.8067871138479035	3.3124414206219872	-0.0861269928738332	0.0526068253056332	
+1.0150000000000001	0.0603129045057476	0.4448535248360507	9.7743543217011126	3.1262795292352110	0.1495341370874131	0.2933380996064647	
+1.0160000000000000	0.0651456028787271	0.5058522163158188	9.7790690965644611	3.3627640546656479	0.0520672521330152	0.0583057576578937	
+1.0170000000000001	0.0857237222544778	0.5304900641493580	9.7935384756587212	3.1124220327407861	0.0359967093931015	0.2886002300235437	
+1.0180000000000000	0.0684512044218408	0.5379487043823065	9.7844097249927220	3.2263663432361294	-0.0153048908571686	0.2751183550438021	
+1.0190000000000001	0.0773636935634247	0.5940984973816718	9.8010922577797484	3.4325529572250848	0.2640708612207053	-0.0770866090567192	
+1.0200000000000000	0.0600098936980849	0.6061041437187971	9.7629929744397117	3.3788754028364951	-0.4289023554951416	0.1266815385737824	
+1.0210000000000001	0.0493046384177628	0.6319031413197236	9.7854217699174395	3.1654320517221386	-0.0713790205456367	0.0504828403821305	
+1.0220000000000000	0.0755079658492874	0.6573306136234207	9.8136907146859897	3.0557870765500699	0.3852751994082371	0.1559686924435866	
+1.0230000000000001	0.0843411476679850	0.6829646630657542	9.7791735465463479	3.2716031428834200	-0.1183926289984999	0.2053820793797361	
+1.0240000000000000	0.0555147879586366	0.7448562910260316	9.7703500232264648	3.4242097208974438	0.0033327723250122	0.0134246238607296	
+1.0249999999999999	0.0819066633211367	0.7652370206563320	9.7948961080074675	3.1029610736056235	-0.2440887256341691	-0.2771370362835008	
+1.0260000000000000	0.0459984473674747	0.7985753022341215	9.7774958463495594	3.1872288658205061	-0.0690894848721174	0.1769521755909388	
+1.0269999999999999	0.0618935477304513	0.8148799145018673	9.7621951075831923	3.2731255121256480	-0.2071252970363614	0.1824427380889324	
+1.0280000000000000	0.0651871561296496	0.8663123993135503	9.7655543940327778	3.2208676620189078	-0.0452098897607187	0.2294242448577591	
+1.0289999999999999	0.0886071181346481	0.8991777555006857	9.7757635961119274	3.2452806811071238	-0.0066823422729419	0.0257787141404039	
+1.0300000000000000	0.0682090584810312	0.9096816687007062	9.7507582387713931	3.4377524959583723	-0.1429237905498966	0.0935369033206853	
+1.0309999999999999	0.0555403756139605	0.9554399308015508	9.7493836161051419	3.1134559855234798	0.0376327382493187	0.0413218552990973	
+1.0320000000000000	0.0600324641372852	1.0025299899752007	9.7599667494185205	3.2765054481364819	-0.0337900627958799	0.1397868325640235	
+1.0329999999999999	0.0738163837931186	0.9914931300251478	9.7591785029899789	3.1130950358338874	0.0208671838532746	-0.0305067535860445	
+1.0340000000000000	0.0510039349669796	1.0393220318983569	9.7380391123128867	3.0624034543468897	0.0443553151232494	-0.0553124043145843	
+1.0349999999999999	0.0729956629498410	1.0727350461985019	9.7453645210786579	3.0458686104790207	-0.0291766572943645	0.1865246866067396	
+1.0360000000000000	0.0574470282476172	1.1082455095953583	9.7425895681053234	3.1717822411081906	-0.1268636859661546	-0.0367182147092600	
+1.0369999999999999	0.0574925264389968	1.1359162161459160	9.7318312764170116	3.2697264493604945	0.0728343328769289	-0.0692799174814589	
+1.0380000000000000	0.0691013537496804	1.1528772908491340	9.7363293633745140	3.3039214666185939	-0.1509548422374115	0.2112290917264981	
+1.0389999999999999	0.0715358687471575	1.1855674192856296	9.7352965508701885	3.1839691930271314	-0.0326143142978306	-0.1716212919521233	
+1.0400000000000000	0.0472440578950045	1.2232571528870031	9.7400202811819145	3.5271457917787057	-0.0722104913503614	0.2972635242738271	
+1.0409999999999999	0.0618539514844021	1.2473008424191947	9.7109415642884915	3.1404421619807716	-0.0920316373213193	0.0463013535731095	
+1.0420000000000000	0.0609252102277009	1.2927976987596737	9.7290280053726015	3.2059145953042116	0.1829587306228989	0.1890325254468715	
+1.0429999999999999	0.0870081402606442	1.3157254392903615	9.7060240167255802	2.9610549802348745	0.0904636884307465	0.1566557378999591	
+1.0440000000000000	0.0685677986752696	1.3248678756017476	9.7055858710342271	2.7132595072473844	0.2920716661357337	0.0281593934876774	
+1.0449999999999999	0.0544717269311976	1.3897745961442978	9.7072433469520405	3.0720930163836724	-0.0237672497190816	-0.0259535671678639	
+1.0460000000000000	0.0712651261040668	1.3854150162880794	9.7232475499424904	2.9662711364201924	0.1185337751819819	0.2591716217416684	
+1.0469999999999999	0.0529796917786235	1.4187605072021898	9.7175766515953494	3.1764251864592912	-0.1187086102167302	0.1804004809925515	
+1.0480000000000000	0.0832186159346922	1.4596946224228191	9.6951274143695549	3.3371134248708625	-0.0446005150625847	0.0746927574334606	
+1.0489999999999999	0.0613086342816179	1.5240823718744243	9.7089876305347609	3.0741205155146232	0.0379922670043156	0.0018747072955645	
+1.0500000000000000	0.0754324170971278	1.5197827228477667	9.6839189077609156	3.0111034058121078	0.0364391415436300	-0.0647735136388209	
+1.0509999999999999	0.0652596307226065	1.5517507354214943	9.6863436587445477	3.2217268859207420	-0.4004716316338089	-0.1042244239203238	
+1.0520000000000000	0.0775847970547024	1.5988119241845216	9.6905211118743022	3.3540426215042016	0.1172338012403938	0.0441831937996761	
+1.0529999999999999	0.0566842662122964	1.6045684856945999	9.6812690512749260	3.1214871921624785	0.2399607528365257	0.2369627402982763	
+1.0540000000000000	0.0727434115846637	1.6464790168482779	9.6598661350026997	3.5249546826167748	-0.0840553312312324	0.1896747687530675	
+1.0549999999999999	0.0820570289286055	1.6808639370460541	9.6653215144031961	3.0959861914696285	-0.1241397450968659	0.0309247814966461	
+1.0560000000000000	0.0674407077723281	1.7182948924343742	9.6934694357780824	3.3614158344889304	0.0981641772805386	-0.2763355850016151	
+1.0569999999999999	0.0546148545226193	1.7205054962339836	9.6650095943816936	2.9740352055282697	-0.1576063774620191	0.1364225383940149	
+1.0580000000000001	0.0711832000292697	1.7741531106876292	9.6526186394423572	3.1251141023427160	-0.1356431257171270	-0.2082021740289433	
+1.0589999999999999	0.0687761418801636	1.8175802260519061	9.6614799859067375	3.1515964154585685	0.2523945116569462	0.2615256465962985	
+1.0600000000000001	0.0687878344001494	1.8238606865672182	9.6484040892830762	3.1394096526336552	0.1760013744317801	0.2315355999511400	
+1.0609999999999999	0.0755460905137727	1.8501136345864639	9.6280055754620566	3.1342080926391844	0.0493818687111322	0.0055541235045442	
+1.0620000000000001	0.0715630085026880	1.9013636675798908	9.6270153736933306	3.1727543015663202	0.1896461533338365	-0.0937803455065899	
+1.0629999999999999	0.0746026401253967	1.9415216483145106	9.6330295756720776	3.0843802450509381	0.0248073204618697	0.0753514171618147	
+1.0640000000000001	0.0864166093652352	1.9694852787653987	9.6224363439808052	3.5993501976357511	0.0271630880720996	-0.0255153391740198	
+1.0649999999999999	0.0618581789670488	1.9747254445825733	9.6067734956673245	3.4100442999769576	-0.1027048268477073	-0.0304190184352004	
+1.0660000000000001	0.0526674799491266	2.0088212263749332	9.6226124594444080	3.2668476955091643	-0.0113142871205552	0.0469664361261483	
+1.0669999999999999	0.0800084111021583	2.0469739183573274	9.5890930583599339	3.2064994822642436	0.1784426274331392	-0.0383893612946426	
+1.0680000000000001	0.0533153846552630	2.0869871773997217	9.5795638159712393	3.2591007849727469	0.0651784434044374	-0.0207548176938867	
+1.0690000000000000	0.0394457462262308	2.1165710172493077	9.6101461211225168	3.2526765397498956	-0.1203858910659326	-0.1812071950727727	
+1.0700000000000001	0.0793064953572791	2.1390733605998276	9.5753165489208190	3.2190683243989180	-0.0316117958103312	-0.0717055356988229	
+1.0710000000000000	0.0486414312367578	2.1838702819449729	9.5545448435169877	3.4363161317321649	-0.0149982391158667	0.0765993296414814	
+1.0720000000000001	0.0767587559064287	2.2105651310660339	9.5827753399649254	2.9027014206556960	-0.0732055781334063	0.2437149431569916	
+1.0730000000000000	0.0505397511494357	2.2315220718602635	9.5566849714480995	3.1921234644515097	-0.0915803477878678	0.0136261117070722	
+1.0740000000000001	0.0834905526550686	2.2466696353315876	9.5293672111948098	3.2337064479219984	-0.1607237636243835	0.2169696453048811	
+1.0750000000000000	0.0711951525596370	2.2436343707471278	9.5362998194798703	2.9802270910476771	-0.1065395032781179	0.1387036831901048	
+1.0760000000000001	0.0444271755653214	2.3212257810510528	9.5288104349594391	3.0249831385814723	0.0536412045231380	0.3175385189700182	
+1.0770000000000000	0.0685853920837388	2.3465475975025707	9.5291681696925821	2.9962369851994377	0.0381181941660400	0.0174636806333269	
+1.0780000000000001	0.0583455573074312	2.3801715550752105	9.5133939270412160	3.0995781797032489	-0.3413834244630947	0.0745348253378661	
+1.0790000000000000	0.0663905819340418	2.4049493407841460	9.5194075380342014	3.1079219765013009	-0.0146608145380243	0.0174250214836091	
+1.0800000000000001	0.0463879951347498	2.4107204190697633	9.5114124952130883	3.4595827346258159	0.0776199849074750	0.1725498794448457	
+1.0810000000000000	0.0496564601401744	2.4686334101112046	9.5021431383079236	3.3651799898909824	-0.0159811397829840	0.1813403077625567	
+1.0820000000000001	0.0820509692097773	2.4896364243641753	9.4736113901170818	3.0268287223485726	-0.1523639622099899	0.1960570133812744	
+1.0830000000000000	0.0603727450502790	2.5338311126544397	9.5014214889271233	3.2747779205388117	-0.0009999761496876	-0.0223166528303872	
+1.0840000000000001	0.0691286851358874	2.5478803861774382	9.4893044980747465	3.0000301020520705	-0.0086690641042360	0.1620670457906168	
+1.0850000000000000	0.0331370569524327	2.6007378571110014	9.4840493246317994	3.1368554982318613	-0.2289574637181802	0.0151200872520892	
+1.0860000000000001	0.0873083838709407	2.6162290019206953	9.4466680870148938	3.1005150546598692	-0.0258543124221445	-0.1146886485710268	
+1.0870000000000000	0.0685241986392790	2.6890438536627852	9.4568274209381755	3.2608413685892441	-0.0068369313923409	0.0027062744518168	
+1.0880000000000001	0.0501809247960263	2.6877196254796787	9.4593464487702530	3.1894315016492456	-0.0915923007890395	0.2009336226462505	
+1.0890000000000000	0.0546199890479525	2.6928278276709188	9.4354610523995177	3.2244760706505691	-0.0634739611552454	0.1164983039198969	
+1.0900000000000001	0.0708724928622611	2.7187015515377206	9.4085914579187229	3.3518575792989536	0.0290421392427696	0.3672794370331191	
+1.0910000000000000	0.0734373926842939	2.7765045900982641	9.4098256052169909	2.9248642802588622	-0.0220918862010587	-0.0031786673322900	
+1.0920000000000001	0.0636059387183257	2.7778575638014114	9.4059872084217986	3.3245251802592146	-0.2142899275391585	0.0485104020658295	
+1.0930000000000000	0.0853487022613867	2.8178867472361340	9.3949330187875031	3.3054741405831574	-0.0818878329249511	0.2634068011704558	
+1.0940000000000001	0.0825935235459273	2.8787623954504946	9.4058240083533597	3.1914237692370846	0.2088196216319593	0.1416174705134760	
+1.0950000000000000	0.0727425499573391	2.8864576617494944	9.3852468989094682	3.0429458479056755	-0.0262885956265806	0.0351445711936927	
+1.0960000000000001	0.0605978887822908	2.9088229445681431	9.3760148571347859	3.1252372122055321	0.0672394179423072	-0.0819368746221852	
+1.0970000000000000	0.0965666469955660	2.9441991878568659	9.3582105495040828	3.3223498422934710	-0.2124412050282956	0.0110752927763077	
+1.0980000000000001	0.0932161114559718	2.9792114834007823	9.3647896118513145	2.9913657924645189	0.0202130552469239	-0.0921776402426292	
+1.0990000000000000	0.0543200582576357	2.9914300735722379	9.3355828388321331	3.2207470053778859	-0.1813198768707063	0.1121584171912690	
+1.1000000000000001	0.0610653285303244	3.0387214833355767	9.3391925029295333	3.0320895852831540	0.0071111304680971	0.0308785497599807	
+1.1010000000000000	0.0764685949358379	3.0464668670646260	9.3264822590106977	3.2009176169219278	-0.1378759664635454	0.1145186697068408	
+1.1020000000000001	0.0547266614377827	3.0757096317937367	9.3082963584106935	3.2273131474613193	0.1963671833668366	0.0328645254584428	
+1.1030000000000000	0.0617397906276431	3.1184381090785327	9.2986261461794371	3.2963486691292059	-0.2029313709855040	-0.0323380497102385	
+1.1040000000000001	0.0693915996227858	3.1098965735654733	9.2996903920366663	3.1942907920686729	-0.1931034397206904	0.1649501261500209	
+1.1050000000000000	0.0766421070068886	3.1794347025107199	9.2902700361537072	3.1522701021967263	-0.0210110003001889	-0.0271879476250556	
+1.1060000000000001	0.0606746305886780	3.1944136731796626	9.2911832877246976	3.1828403514418548	-0.1178236335240638	0.1188032309236994	
+1.1070000000000000	0.0836616270520625	3.2364473588617382	9.2752652465447607	3.3538948407235272	-0.1060269984008123	0.1691558013668140	
+1.1080000000000001	0.0594936970011861	3.2640983543073294	9.2518690064559355	3.1258839973189287	0.1148327968882199	-0.3111347372129317	
+1.1090000000000000	0.0485739075981115	3.2752177930162154	9.2560593325138747	3.1662775922517983	-0.0964297449300521	-0.0210464184945939	
+1.1100000000000001	0.0488156133879222	3.3003565321439865	9.2375571904308202	3.1655380906140462	-0.2753059641927285	0.0422782499801511	
+1.1110000000000000	0.0706575032548805	3.3573913976556753	9.2452204644434861	3.3807261047103934	-0.1635420383548990	0.2176411769472337	
+1.1120000000000001	0.0604972538891947	3.3952308970639429	9.2118750047405502	3.1047665337011412	-0.1613091557471859	0.1579876518149472	
+1.1130000000000000	0.0610100500251397	3.4036347670803200	9.2126114460442761	3.0459077163116954	0.0290448531459077	0.1283861512942395	
+1.1140000000000001	0.0691349811481661	3.4243850229063142	9.2052490120781592	3.3097481161134348	-0.2146158693242192	0.1658960833028897	
+1.1150000000000000	0.0533675243086244	3.4578752259809278	9.2007042581551399	3.2101521488092990	0.0466449677207789	-0.2767701002869880	
+1.1160000000000001	0.0711370562961802	3.4833615806491336	9.1650159893961796	3.0469110757702471	0.0711805466131451	0.0717933622795550	
+1.1170000000000000	0.0595008816719495	3.5091462973853798	9.1731698970540521	3.1920938083870065	-0.0224354408006999	-0.1329837549722035	
+1.1180000000000001	0.0618541317097199	3.5437809083348450	9.1364817981877877	3.1369887841804700	-0.0672121445400712	0.0013992736560937	
+1.1190000000000000	0.0801299220254497	3.5643357408185810	9.1168491984187874	3.3558781765011947	0.0659145981304304	0.0376168776744277	
+1.1200000000000001	0.0801917662702098	3.6030590736893826	9.1314349367385681	2.8898065956182162	-0.1739742409295033	0.3615163261437025	
+1.1210000000000000	0.0538611841109990	3.6446000705919555	9.1307170266095898	3.2092054049318772	-0.0555064423803569	-0.1065521468449150	
+1.1220000000000001	0.0502676562148791	3.6581344722548739	9.0862286053160197	3.2191365736190618	0.1836981456408516	0.0038109793277609	
+1.1230000000000000	0.0594868801446875	3.6877569734256528	9.1022379299798928	3.1433170382619053	-0.0860265962704745	0.1464357279251793	
+1.1240000000000001	0.0591940827428023	3.7204837944624538	9.0923745293130835	3.3158705579151189	-0.0834114674119071	0.0131994778403375	
+1.1250000000000000	0.0558312798153161	3.7682559767849972	9.0520068352150922	3.0821114274160579	0.0290095789410696	0.1062218112499698	
+1.1260000000000001	0.0564551847045838	3.7851658377579716	9.0724057536056453	2.9641861304358823	-0.1946676318842802	-0.2060872553920968	
+1.1270000000000000	0.0540240597880563	3.7996166432930587	9.0589428432476815	3.2046662209520136	0.1255179160884732	-0.0310680304213004	
+1.1280000000000001	0.0712103878381623	3.8447931645100164	9.0257553946784466	3.1490742364113702	-0.2041080323490614	0.0045809597041063	
+1.1290000000000000	0.0667777162258354	3.8599973942511903	8.9996052325088858	3.0850148882865587	0.0390333337318732	0.0662132075188612	
+1.1300000000000001	0.0743844419770088	3.9066098779563552	9.0097028328820929	3.2108793147579746	-0.0461842017718971	0.0121641750353286	
+1.1310000000000000	0.0594263984692255	3.9174815162964975	9.0116594295696260	2.8246716809188994	-0.2214515518464077	0.2679173156670835	
+1.1320000000000001	0.0774450529441471	3.9509713040964525	8.9601387993924302	3.0340640570107991	-0.1036799536610193	0.3446862294340040	
+1.1330000000000000	0.0500926050655559	3.9690604708309709	8.9785914761537313	3.1112007218137396	-0.0839491826004061	0.3475851856758678	
+1.1340000000000001	0.0555001948316445	4.0216665058765173	8.9815761660128661	3.2755873661044927	-0.1882861364853289	0.0169316524787866	
+1.1350000000000000	0.0584300515415005	4.0344754138548176	8.9363713053386054	3.3699415772141790	-0.0576027109529924	0.3187012542864749	
+1.1360000000000001	0.0583138140594445	4.0443674036524122	8.9231465781464951	2.9834591299355657	-0.0496137511930140	-0.0592796130457656	
+1.1370000000000000	0.0687747217088395	4.0734921850173400	8.9134802211396043	3.1784045236322780	0.0765034681803176	0.1661248642482111	
+1.1380000000000001	0.0403698003051118	4.1226687712989500	8.8925382771704378	3.2053637507096133	-0.0204504235098347	0.1559552082225349	
+1.1390000000000000	0.0880873750021939	4.1313198244438514	8.8981306590888991	3.3060402727098475	-0.0752095066073911	0.1265289499156025	
+1.1400000000000001	0.0656878928032466	4.1879900541692532	8.8656813018532628	3.0705637187689798	-0.2202038687752131	0.1927452584746515	
+1.1410000000000000	0.0543128338068258	4.2020233665689393	8.8693820353408572	3.1762730478773502	-0.2803055126419741	-0.0438974519966390	
+1.1420000000000001	0.0638965938965337	4.2287514884876849	8.8526297514028833	3.1850511291857431	0.0704302775575320	-0.2101065796262317	
+1.1430000000000000	0.0477811639868696	4.2707382099164919	8.8544412707061202	3.0699800083069584	-0.1700550876550313	0.1706821742307657	
+1.1440000000000001	0.0550083321925913	4.2981923834000524	8.8380338072251785	3.1634256612802902	0.0960468147265438	0.1084105908198784	
+1.1450000000000000	0.0653616124444863	4.3316281287041356	8.8265682812403252	3.3877379396690737	0.0714682440369610	0.2571527530549419	
+1.1460000000000001	0.0648108550837868	4.3417169101570092	8.8085207804236632	3.1472311260478345	-0.1360774857704563	0.1125837676137090	
+1.1470000000000000	0.0634748443810572	4.3427491450445288	8.7900982620072163	3.1485944249519267	-0.0505051067827154	0.0959385845390667	
+1.1480000000000001	0.0660650636896336	4.3941260783242306	8.7775857028581346	3.1624969274199324	0.0266464583755738	0.1621118619881979	
+1.1490000000000000	0.0767911256619574	4.4175543439496252	8.7401077853642537	2.9403260720772684	0.2216710592705143	0.1745722981881390	
+1.1500000000000001	0.0601432464331750	4.4354491218680483	8.7610296155323244	2.8134761827604597	0.2011080982178455	0.4777294624571102	
+1.1510000000000000	0.0679609958818767	4.4660682751931171	8.7370847162951844	3.3669005010424096	-0.0842183567468794	-0.1803758426565248	
+1.1520000000000001	0.0785021780754073	4.5204169870964135	8.7113786662854746	3.3146011278048801	0.0059123746950242	0.1102921950460138	
+1.1530000000000000	0.0612344550756252	4.5326192129719276	8.7173658555009261	3.1810683292506599	-0.2547338625050827	-0.2363661951513206	
+1.1539999999999999	0.0758447736489616	4.5479109372965407	8.6981791150607766	3.5092151823535094	0.0508608881035089	-0.0021204720415850	
+1.1550000000000000	0.0646272131556134	4.5857922107202560	8.6867263795217937	3.2164604663124061	-0.1012392960584901	0.3353946645985569	
+1.1559999999999999	0.0593560124281570	4.6062528771404265	8.6568773462847908	3.1501274165878868	0.1081050648994822	-0.1940284390413524	
+1.1570000000000000	0.0815284084930331	4.6574363402045602	8.6503554641494151	3.0477938291639139	0.1797570146831100	0.0279321307169173	
+1.1579999999999999	0.0692788283591332	4.6684729401528902	8.6419749383446494	3.1968681237899643	-0.1330250535196444	0.1875450281475423	
+1.1590000000000000	0.0445743328767271	4.6910452322267258	8.6295541546092149	3.3750314015875942	0.0014590828678248	0.1976528235865314	
+1.1599999999999999	0.0839150800149265	4.7397715271191361	8.5971065173954511	3.2395063011978014	-0.0011520210040243	0.1003759501103137	
+1.1610000000000000	0.0852568657329551	4.7340654069158701	8.5974531686874798	3.0686543437098472	-0.1511680655266960	0.2241999124704234	
+1.1619999999999999	0.0758741479301685	4.7910678826216522	8.5736013313324531	3.1087601086958432	0.1161555252117385	0.0810081952562277	
+1.1630000000000000	0.0777560609318080	4.7835780126227796	8.5526024824739668	3.2141871559723083	-0.0457566712008269	0.0022068330417820	
+1.1639999999999999	0.0577911672904782	4.8321074703659743	8.5277121404586680	3.2577030923221493	-0.1605301326958946	0.1825289084479483	
+1.1650000000000000	0.0605404717666142	4.8217522513219295	8.5392690323975096	3.2305478346742458	-0.0325883229758368	0.0688430829507211	
+1.1659999999999999	0.0680673240401989	4.9022591549208077	8.5211884731952772	3.1536146664891547	-0.0497984369358306	0.3383524390959958	
+1.1670000000000000	0.0524857111613087	4.9017031879554018	8.4871829950422555	3.1737423530628877	-0.1437185579489385	0.0996396231898824	
+1.1679999999999999	0.0613453959142848	4.9395083101500754	8.4808128140077859	3.2695059284051773	-0.2911766842941098	0.0493121792839387	
+1.1690000000000000	0.0486598418567969	4.9509596197432497	8.4737575979077349	3.2612917532300654	0.0893415503650212	-0.0064885436793089	
+1.1699999999999999	0.0576308845013935	4.9745695960962157	8.4626243080394605	3.0163617910803469	0.1336536211271565	-0.0608447586987850	
+1.1710000000000000	0.0631391451156955	5.0064019536171047	8.4240965227112650	3.2911670363353980	0.1384505052724201	0.3802025247671481	
+1.1719999999999999	0.0672159736077306	5.0539233101167707	8.4328306800412811	3.2970606566702125	-0.2312277494010658	-0.0712790486507310	
+1.1730000000000000	0.0542889224538660	5.0659659870174929	8.4090459983161878	3.2036413427461667	0.0777449491221305	0.3514171907344004	
+1.1739999999999999	0.0535887208353692	5.1066639607932638	8.4032941674856705	3.3274212830870127	-0.1885199208981769	0.2417522521429468	
+1.1750000000000000	0.0569514550618367	5.1298604362189755	8.3905028327108937	3.3607982594210171	-0.2859233051359053	0.2377964640377065	
+1.1759999999999999	0.0554152320615783	5.1464386106391684	8.3448080467075236	3.1714049146091745	0.2154324111109486	0.1386174580871998	
+1.1770000000000000	0.0280418802987956	5.1932035974963018	8.3272780196369709	3.1147690294934565	0.1176172497539300	0.3621143650731965	
+1.1779999999999999	0.0939539158298027	5.2407457138254090	8.3408713819022164	3.1573126594785528	-0.2527126946854522	0.2705918905921146	
+1.1790000000000000	0.0663362153747726	5.2344671498987063	8.3249271569003866	3.5775818674520892	-0.0073560223674311	-0.1204759442354544	
+1.1799999999999999	0.0775909042617763	5.2426626059516916	8.3015924502004150	3.3853448121530199	-0.3653450941715196	0.0728661712146721	
+1.1810000000000000	0.0782443949577570	5.2834575569680204	8.2656233726167816	3.2763582360307861	-0.0478949105475710	-0.1333577222806144	
+1.1819999999999999	0.0642460657026552	5.3067809840185900	8.2737285360967867	3.1146626215079971	-0.3230067911416646	-0.0449671036496913	
+1.1830000000000001	0.0607436680561670	5.3320496092217802	8.2429731936155566	3.2874704809883677	-0.0571838045558396	0.0254189100880672	
+1.1839999999999999	0.0846198866632868	5.3381555604046413	8.2171518914743231	3.0465543066327325	-0.1915432831014251	0.1171822207899716	
+1.1850000000000001	0.0524312330467406	5.3689538622871957	8.2082759980058491	3.4356495458614513	-0.2325338057773431	0.2039605173469173	
+1.1859999999999999	0.0612816149949611	5.4262613323220794	8.1916469906017912	3.4905335477349397	-0.0254034764665786	-0.2274820068587710	
+1.1870000000000001	0.0712275462109728	5.4329486885563005	8.1807558125939224	3.1263598190000312	-0.0071619806175023	0.1049389709384610	
+1.1879999999999999	0.0696649623414362	5.4613959384566622	8.1574515160795009	2.8345748386787926	-0.0515164797949741	-0.0168037663517270	
+1.1890000000000001	0.0778968965239320	5.4758857795207163	8.1624391928052873	3.3817747932598308	-0.1664735413450460	0.1205052044849949	
+1.1899999999999999	0.0796521994472003	5.5190847165048345	8.1212603008832343	3.3826674118598645	-0.2385019065318184	0.2441453059846559	
+1.1910000000000001	0.0621842088472929	5.5443153436395241	8.1277635200587390	3.1021414818035762	0.0629783521115007	0.3955322368394488	
+1.1919999999999999	0.0592938683102946	5.5774793742415056	8.0700863611172355	3.4768590624539359	0.1507156970395203	0.0415899716854968	
+1.1930000000000001	0.0710138868218163	5.5855179286216430	8.0661451654382255	3.2602475692279618	0.0377111153714159	0.1748396548059099	
+1.1940000000000000	0.0573545245003323	5.6179395778073387	8.0601354073280049	3.0521984757148570	0.1265884318027024	0.1117179635443306	
+1.1950000000000001	0.0808077190877924	5.6506966419978450	8.0458736752619977	3.1687003688167183	-0.1282525741117350	0.0876268673755964	
+1.1960000000000000	0.0725133757895884	5.6561961323695469	8.0467594825312361	3.2525372035819347	0.1389595114349152	0.2568611428674894	
+1.1970000000000001	0.0433318788282230	5.6774025302190623	7.9978701466858331	3.2469183579438767	-0.0837891935893698	-0.2241217913835661	
+1.1980000000000000	0.0491847104351300	5.7212393653501046	7.9815248618394632	3.2655958617458030	-0.1055038912826294	0.0078762951854102	
+1.1990000000000001	0.0438098568675907	5.7580079471675383	7.9784433097043888	3.4028018203252830	0.1502247005158361	-0.2214605461190005	
+1.2000000000000000	0.0560829654983033	5.7614111926748519	7.9439896441663098	3.2382016692455329	-0.0054191541028785	0.2671181816134778	
+1.2010000000000001	0.0570176446412627	5.7894857094204237	7.9307010766222419	3.2500556644176077	-0.1257083468801309	0.0660058784471322	
+1.2020000000000000	0.0651049512680641	5.8231425704253841	7.9155750695532019	3.1702535449470530	-0.2398277895106292	0.2580271454651696	
+1.2030000000000001	0.0581747657375103	5.8262234944181790	7.8917601929590981	3.1166824550173167	0.2440987560306368	0.1060342393796677	
+1.2040000000000000	0.0494055271880492	5.8534814986463770	7.8919001173141572	3.1354720080302778	-0.0070729379121212	0.0941238329934037	
+1.2050000000000001	0.0646509656445068	5.8814346585314432	7.8602569835002747	2.9943377868097998	-0.0173649431036946	0.2106945908771427	
+1.2060000000000000	0.0536301917436046	5.9048454719256407	7.8434435678967818	3.1732303633479804	-0.2800053117299484	0.2396572468403511	
+1.2070000000000001	0.0610872840377131	5.9416909043326651	7.8363518223658293	3.2394194037166066	-0.1612871458049023	0.0693851339034070	
+1.2080000000000000	0.0692682816544819	5.9745518416439243	7.8097354341242102	2.9492096423513905	0.0288858379229327	0.0318269046261923	
+1.2090000000000001	0.0311766794742410	5.9804373869837839	7.7987576674051473	3.2441067277923032	-0.2264723642871965	0.0551054880782856	
+1.2100000000000000	0.0659296919523861	6.0249350499173380	7.7521453153107842	3.0214150129107384	-0.1874976792636066	0.0922199834249590	
+1.2110000000000001	0.0798939237805245	6.0424991705301716	7.7468982871376406	3.4220110601466400	0.0428680439270944	0.2121504228890380	
+1.2120000000000000	0.0618185380540810	6.0577155678594705	7.7294944141807802	3.2173269394243795	0.0646417018108589	0.2916351705842720	
+1.2130000000000001	0.0686445139009215	6.0935548183665862	7.7080704714971038	3.1703570315511036	0.2171575528039365	0.2114452685668978	
+1.2140000000000000	0.0848374350332341	6.0947082680636706	7.7185449712599450	3.0836922622264100	0.0036077048014461	0.0806962171435863	
+1.2150000000000001	0.0393446982089034	6.1262637206370218	7.6666188670518540	3.0348118012426868	0.0436150567536202	0.3198139273604294	
+1.2160000000000000	0.0739832133152710	6.1558923283355975	7.6407094188268960	3.1963847351943051	-0.0623930259804085	-0.0044297336839929	
+1.2170000000000001	0.0727717657101538	6.1792702089399079	7.6310750112696040	3.0234776492678561	-0.1195809554114229	0.1280178275527591	
+1.2180000000000000	0.0562176165107701	6.2203925327879022	7.6240384358001458	2.9733382404030926	0.1420087766237685	0.2935910538870983	
+1.2190000000000001	0.0788061911279499	6.2246281034068343	7.5861321020283201	3.0766622007885194	-0.0404577399567164	0.3289426126406666	
+1.2200000000000000	0.0811867480802377	6.2331279919152500	7.5849054193825083	3.3372189515567103	-0.1435415811512108	0.0253425469713094	
+1.2210000000000001	0.0614307594348395	6.2725769967560954	7.5481252815837063	3.1049603663272305	0.2249619094067313	0.0530318497156643	
+1.2220000000000000	0.0681001537992835	6.2859416446165151	7.5552581483163710	3.1532956093853493	0.0509255780539497	-0.0616920342424670	
+1.2230000000000001	0.0561969115501141	6.3280343263680123	7.5160587377683310	3.0924488906922880	0.0184151280685914	0.4157386128739788	
+1.2240000000000000	0.0816695059611101	6.3262338410560970	7.4932542124842829	3.0819266393666949	-0.0700447248960016	0.1764211112004573	
+1.2250000000000001	0.0577762113807678	6.3899349463237360	7.4617253923109148	3.2802108614921273	0.0344714285591868	0.2580164002706550	
+1.2260000000000000	0.0473816989839352	6.3794172512253766	7.4468933552690331	3.1974055337941336	-0.0597949368547668	0.1583015779334683	
+1.2270000000000001	0.0904569538016505	6.4132272036321964	7.4470438889283121	3.0305149657066326	0.0392256143875197	-0.1824403401294324	
+1.2280000000000000	0.0553115341816470	6.4360972181145133	7.4290892959429922	3.1386459301707554	0.0031873791066748	0.2774715059422456	
+1.2290000000000001	0.0645322719132320	6.4600354750896090	7.4034152773038171	3.2330249708591374	-0.1211052873844171	0.1793916676694637	
+1.2300000000000000	0.0688003473648944	6.4763616282249075	7.3747842085078776	3.1212626977727465	0.1629658096436146	0.1938813941065232	
+1.2310000000000001	0.0442358213406038	6.5027652745844042	7.3377572356367056	2.9893028924747269	0.0970525446034902	0.2563203136871390	
+1.2320000000000000	0.0684636989151978	6.5324008848715120	7.3305860391701874	3.1152831163300245	0.0202125483231376	-0.1493120643475652	
+1.2330000000000001	0.0659897157592542	6.5442248993668652	7.3291746177199029	3.3658795014403071	-0.0610344033794841	0.5299304119787759	
+1.2340000000000000	0.0570060354045815	6.5660084263569631	7.2785782287060057	3.1691138616956462	0.1139483749853512	0.1862890018570829	
+1.2350000000000001	0.0633910315187233	6.5933489020888096	7.2626050180766253	3.0955714333795346	-0.1311744591616464	-0.3803504157112095	
+1.2360000000000000	0.0553057427485133	6.6404939332123423	7.2389666457131971	3.3935392267996138	0.2220066659678864	-0.2126099036054733	
+1.2370000000000001	0.0734031197534951	6.6525137332988962	7.2527484173386485	2.9228402545937175	-0.0575680138647826	0.1806758038585863	
+1.2380000000000000	0.0589200964716777	6.6744250754258587	7.2349319584097609	3.1272411811005658	-0.0597974613916359	-0.0500773910247135	
+1.2390000000000001	0.0795543762018472	6.7074070798571697	7.1876943150616377	2.7861092589807686	-0.0435451231843928	-0.0935326517360214	
+1.2400000000000000	0.0645771632461005	6.7090191374089709	7.1926825828629308	3.4363026035919391	-0.0268384176041056	0.1343088315060034	
+1.2410000000000001	0.0601505365072496	6.7230388272196668	7.1636092935992339	3.3103883402991006	0.0323532712787532	0.1932436668362115	
+1.2420000000000000	0.0772261674076345	6.7733332832064521	7.1243552651833983	3.1733335044254214	0.1544222147699989	0.0720225373877178	
+1.2430000000000001	0.0728232820596134	6.7932818234149854	7.1289380377793945	3.1852476517890342	-0.2360689530975656	0.1306143565636816	
+1.2440000000000000	0.0518927149478790	6.7834362111055651	7.0784850093340719	3.2168077101326600	-0.3416447366579072	0.0501677564610541	
+1.2450000000000001	0.0787612253156366	6.8339321162630258	7.0680708647611388	3.2994573064409298	0.0629710206046275	0.2218713964884158	
+1.2460000000000000	0.0818357856451416	6.8448817275768983	7.0395191340944594	3.0269600906272109	0.0981633723992326	-0.2546342801550254	
+1.2470000000000001	0.0336162639291837	6.8584508250117251	7.0143010972577144	3.5328305266069817	0.0421626722658166	-0.1082568571566261	
+1.2480000000000000	0.0622481063718474	6.9121832041374223	6.9967874588387424	3.0848055226063389	0.1396070692611072	0.2591355950333543	
+1.2490000000000001	0.0675440637367727	6.9211788481214347	6.9689351354321349	3.0129747635516035	0.1465409039295873	0.3055179323124783	
+1.2500000000000000	0.0709050993364938	6.9150137447087037	6.9404267135605515	3.1680065869740779	0.0078370320274078	-0.1842275375360223	
+1.2510000000000001	0.0504418924178075	6.9353788201658606	6.9248255384335398	2.9905976880637524	-0.1188276587411011	0.0847408431696080	
+1.2520000000000000	0.0747686306153181	6.9585112248138756	6.8972915196979603	3.0217817591576646	-0.1200662737001338	0.0158227827844188	
+1.2530000000000001	0.0825562478724279	7.0012305493255749	6.9070793832966402	3.3456033623247690	0.2151929285104533	0.1155136939228857	
+1.2540000000000000	0.0704295314058949	7.0092305513379136	6.8638312958822558	3.0693502745940808	-0.0658886811329487	0.1181944599592245	
+1.2550000000000001	0.0507869703384472	7.0269269624208928	6.8391283260015534	3.2923352078324442	0.0435769051341050	0.1876573240374511	
+1.2560000000000000	0.0899545993304801	7.0618895685993373	6.8365456379161635	3.3662297552542908	0.1491752433376957	0.0797224296481534	
+1.2570000000000001	0.0629311593923654	7.0818063015615813	6.7983299247499787	2.7762381796488702	0.1389771944084840	0.2616124170634209	
+1.2580000000000000	0.0538633896233101	7.1086687068934165	6.7808983529700324	3.3288499309971242	-0.1191989199724736	-0.1131371410920078	
+1.2590000000000001	0.0598664881141915	7.1267460677439907	6.7735877803012432	2.8249875707389922	-0.2711651145267506	0.1668497649937437	
+1.2600000000000000	0.0806057583895548	7.1753633901685063	6.7234271237099241	3.1540692430095820	-0.0520313336753206	0.1564797777403848	
+1.2610000000000001	0.0526749586046518	7.1901939063058693	6.7149599122781876	3.4374228581763830	0.0085809880141265	0.1212710731243808	
+1.2620000000000000	0.0619703955164683	7.2123677143138778	6.6760759498485820	3.1934772436566967	-0.2048230759801670	0.0092306838605897	
+1.2630000000000001	0.0453843937897552	7.2083081558940032	6.6431702630419407	3.0217337836934406	-0.0670629568091770	-0.0467058554051904	
+1.2640000000000000	0.0595205490944581	7.2299002481416057	6.6344740022649011	3.4097600932259970	-0.2153318362308569	-0.0715285710001162	
+1.2650000000000001	0.0633601304238875	7.2540626337154670	6.6361315587284606	3.1083439546926637	0.0952821010392067	0.2388652084973872	
+1.2660000000000000	0.0692203349007311	7.2947722786871516	6.5806073726069005	3.1344808591959810	0.2526190533516913	0.2547814310841729	
+1.2670000000000001	0.0755634385183488	7.2919397993686639	6.5754174169854691	3.3693692976453185	0.0913414308639867	0.4161198119189368	
+1.2680000000000000	0.0476646904226324	7.3469698582485456	6.5444877837724231	3.1399777588929929	-0.1198598241810749	0.0006468296793463	
+1.2690000000000001	0.0505653482175945	7.3148074114565000	6.5250931752305856	3.0702275450963468	0.2339425139716843	-0.1652779767281987	
+1.2700000000000000	0.0553017356837151	7.3484951293085254	6.5068340657070278	3.2661783399427793	0.0732395798644919	0.1329596564214423	
+1.2710000000000001	0.0556439361219442	7.3630630077586634	6.4693281721174731	3.1769488283364167	0.0079300864039803	-0.0743128999954695	
+1.2720000000000000	0.0599325240904260	7.4128458406218272	6.4411432913412732	3.1471023235736020	0.0026712304650359	-0.0009253475646954	
+1.2730000000000001	0.0598236422113195	7.4115353850377650	6.4305529696350971	3.2669128503983407	0.0562492319797211	0.2105026667750348	
+1.2740000000000000	0.0495043679271804	7.4200663566815814	6.4294452200411092	3.2146218455298117	0.0280983067299182	0.1365080312254376	
+1.2750000000000001	0.0559637630051011	7.4515030613815343	6.3904330927823194	3.1516991483820815	-0.1997746486651211	0.1318382652529297	
+1.2760000000000000	0.0847793418650866	7.4638586362236463	6.3683245437916476	3.2766088096991788	-0.0278623946100239	0.4061101974413572	
+1.2770000000000001	0.0517346702672535	7.5021783293077604	6.3480854396033521	3.2577328312661740	-0.0636188422126331	-0.0717133607325416	
+1.2780000000000000	0.0617430623172921	7.5303226855637666	6.3348215817290203	3.2527408527277082	-0.0326215689828862	0.2303082047546979	
+1.2790000000000001	0.0559954571884242	7.5493270790343692	6.3170429264102310	3.1304029793677146	0.2505179361264704	-0.1836930897792748	
+1.2800000000000000	0.0546238417827018	7.5394141561424659	6.2889580812292918	3.3219365993072718	0.0285871453473176	0.2847187615922248	
+1.2809999999999999	0.0757110300901017	7.5901618425734183	6.2560399002478375	3.2556582875731861	-0.1128201954064565	-0.0714302144936397	
+1.2820000000000000	0.0524085215073666	7.5985987418144285	6.2260588927264164	3.2885933251939523	-0.0848392685907549	0.1353446658506244	
+1.2829999999999999	0.0779417015952899	7.5883691081363409	6.2083741852873029	3.2188140080101997	-0.1745995856622514	0.1173204411073513	
+1.2840000000000000	0.0516977770689914	7.6344526804387813	6.1824707655269346	3.1608863921753327	0.3119252584815140	-0.1777031588636665	
+1.2849999999999999	0.0456947262266527	7.6604887113279334	6.1596758271332970	2.9800758237572285	0.3171508895337149	-0.0658759052021023	
+1.2860000000000000	0.0799195209205764	7.6566602855221504	6.1326954247016161	3.0432960632100796	-0.2191122715021148	0.2512935628538328	
+1.2869999999999999	0.0554790177598964	7.6984159413303237	6.1126700686445989	3.3050080723767805	0.1046532662602703	0.3958193438730798	
+1.2880000000000000	0.0624707194509203	7.7223590657907941	6.0589767565983346	3.1804150921301124	-0.0380331225712734	0.2154321332951485	
+1.2889999999999999	0.0625767025885789	7.7124376752493546	6.0446270883000324	3.0231800212761843	-0.0185865188587110	0.1253487328686020	
+1.2900000000000000	0.0792704670604878	7.7372873609049186	6.0359571315146567	3.1744174981575806	-0.1012974968625736	0.1659459802999620	
+1.2909999999999999	0.0613116068310995	7.7993233885918647	6.0073869345726578	3.3665385913068739	-0.1105052823094148	0.2774076615638628	
+1.2920000000000000	0.0813214625591893	7.7875871869473912	5.9860876480835383	3.2542260223741399	-0.0598546792046100	0.2511537830913056	
+1.2929999999999999	0.0567265964509725	7.8137951139197916	5.9493962439697397	3.2728721609766813	0.0098737931428861	0.2133700093940751	
+1.2940000000000000	0.0415804644583453	7.8041310370080756	5.9451030260221520	3.1919244687876507	0.0556796446511586	0.2950382704288545	
+1.2949999999999999	0.0758452015004031	7.8364895085766104	5.9447725577444901	3.0677750188333022	-0.0946903703022201	0.1867822064346452	
+1.2960000000000000	0.0673095937433618	7.8664070665856514	5.8833242820242413	3.3514279679486911	0.0218893249470762	-0.0793350736836499	
+1.2969999999999999	0.0575867771440672	7.8819263244911131	5.8726512047365294	3.0746580555355605	-0.2469058638716468	0.0102830534339947	
+1.2980000000000000	0.0429710213169535	7.9073920950473910	5.8192217524438306	3.1527439912852029	0.0383246038693973	0.2691522861255712	
+1.2989999999999999	0.0701604170736806	7.9280392892535776	5.8162739023357721	3.2862530211013046	-0.0283777056037510	0.2503761126556172	
+1.3000000000000000	0.0683102574855971	7.9432705189400972	5.7775422055128827	3.2195552509741598	-0.0486192560488602	0.1706524995296191	
+1.3009999999999999	0.0561199740601784	7.9663592661765650	5.7550050863908160	3.2332825156083720	-0.1525866411330916	-0.1385502454933460	
+1.3020000000000000	0.0812606101863405	7.9790002157178650	5.7497661244105780	3.2837927154337518	-0.0301818436159058	-0.1304000292632673	
+1.3029999999999999	0.0535496393748252	8.0084089414771586	5.7241484616066494	3.1812687930629120	-0.0932455033825662	0.0843499987584973	
+1.3040000000000000	0.0563718981421367	8.0081861879746121	5.7018679737395246	3.4117982106803777	0.1209982899859510	0.0620798562584484	
+1.3049999999999999	0.0713356823869870	8.0305429586189323	5.6575647675894887	3.1142775521037178	-0.1694182849983293	0.0950034962985369	
+1.3060000000000000	0.0735778612035418	8.0642948554011458	5.6284221222811075	3.3535443574960206	-0.0050502733451031	0.1542554145728132	
+1.3069999999999999	0.0617510830027440	8.0438420306839475	5.6127102726782869	3.2539704003155348	-0.1481592114024657	-0.3658704130193851	
+1.3080000000000001	0.0814046461376005	8.0840221558820851	5.5938791857079071	3.1397619702237280	0.0730962447883784	0.1414884687375347	
+1.3089999999999999	0.0656180413157245	8.0789658260795409	5.5720835646608915	3.2598712595085697	0.2013160502647121	0.2639301103193022	
+1.3100000000000001	0.0441773920569324	8.0996585708918776	5.5344685061650187	3.3136004356060487	-0.1995655542827214	0.0805827904324782	
+1.3109999999999999	0.0516445405107860	8.1515784030557690	5.5097035941416728	2.7993686357179159	-0.0830748493923668	0.2030927867565307	
+1.3120000000000001	0.0706322494917584	8.1477941858662088	5.4724744357023036	3.4534190701618677	-0.0112926717324005	0.0244986228825742	
+1.3129999999999999	0.0393915906756544	8.1679530464307426	5.4769580816915999	3.0549209892114004	0.0349702255231558	0.0320056696198299	
+1.3140000000000001	0.0652322178120577	8.1906562304047963	5.4529562603310593	3.0384452951070271	0.0535630740187870	0.1920053297798674	
+1.3149999999999999	0.0397434889836971	8.2026475373345367	5.4239049216686652	3.3346576956313925	0.3125589053021520	0.1928498337815880	
+1.3160000000000001	0.0474545861232385	8.2198175294413058	5.3843071917300884	3.3755310134561758	0.0114597356970178	0.0296414033923192	
+1.3169999999999999	0.0588857198043229	8.2408808442769264	5.3584905674914349	3.0725870873696595	-0.0615404231960294	0.2536078356470065	
+1.3180000000000001	0.0655825406872966	8.2541571640985083	5.3307655061316463	3.3435042548940035	-0.0836221733157596	0.1017073031414849	
+1.3190000000000000	0.0759935894123223	8.2610998216736231	5.3000115662960496	3.1816896818012741	-0.3250573526052784	-0.1589987641122041	
+1.3200000000000001	0.0812691511513524	8.2954835819164430	5.2663994105467129	3.1975138004489629	-0.0921206631772534	0.3953123106724545	
+1.3210000000000000	0.0503098350680116	8.3467218450750540	5.2602993336996988	3.0721533255048001	-0.1121241491320730	-0.0669652247924502	
+1.3220000000000001	0.0897566633072959	8.3209357358804681	5.2270367537654341	3.2423822807504736	0.0791577791955029	0.1076200932616670	
+1.3230000000000000	0.0694958388359464	8.3323065622812020	5.2077248224684647	3.2466360297068824	0.0584594493756330	0.0877799476629221	
+1.3240000000000001	0.0753846394064847	8.3486983932262557	5.1799405881168274	3.3835096131981452	0.0031534772454588	0.1642510786948619	
+1.3250000000000000	0.0505888986892048	8.3822371710897432	5.1576695145651517	3.3139322217390976	-0.1308026975321442	0.0895924273550342	
+1.3260000000000001	0.0697554594624558	8.3737296268111816	5.1293691755172999	3.1085153390104128	-0.2504093961440505	0.0031838156405877	
+1.3270000000000000	0.0544136827294427	8.4247826759766333	5.1112729245784188	3.2470444977091901	-0.0872861247582952	-0.2000156820888751	
+1.3280000000000001	0.0834271601451483	8.4067761833294750	5.0770124368250125	3.1000646000342269	0.0023158542991535	0.0385846151964562	
+1.3290000000000000	0.0523532212191602	8.4371427316091427	5.0339132345362803	3.4162071605869060	-0.1565642581422503	0.1142110603518973	
+1.3300000000000001	0.0647313006324913	8.4504818569954967	5.0013692237379503	3.4076398491876265	0.0141022921787686	-0.0238689500601056	
+1.3310000000000000	0.0647185747373038	8.4585835098433826	4.9782700745146222	3.0193734600717033	-0.0094689736011821	0.0051872859830292	
+1.3320000000000001	0.0729566543997810	8.4714973784432210	4.9701952962638796	3.2345766042572053	-0.1726757258728575	-0.0948540161955940	
+1.3330000000000000	0.0595986773614885	8.4947058326916576	4.9252860553540145	3.3165100686045053	-0.1306942404496814	0.1000831217083621	
+1.3340000000000001	0.0375461969926443	8.5097273199933205	4.9016177133351349	3.4275105761137428	-0.0151781908017952	0.2624888988841895	
+1.3350000000000000	0.0442548544379087	8.5436626968225777	4.8813627710485550	3.1311729450643146	0.1352615295531344	0.0592153761371066	
+1.3360000000000001	0.0773913205417664	8.5363025610908920	4.8739994017675965	3.1871788564199028	0.0956440734129579	0.2675206271885258	
+1.3370000000000000	0.0746061550146460	8.5499489319471085	4.8423843075827202	3.2847662458708400	-0.0241793272071428	0.2391553441044860	
+1.3380000000000001	0.0653214061592683	8.5741478717115616	4.8200023978747559	3.1035951554572150	0.1197161224589738	0.0900836799075757	
+1.3390000000000000	0.0642149893623433	8.5783709339000431	4.7681252202392175	3.2823942416331735	-0.1671888552713551	0.1036896255677341	
+1.3400000000000001	0.0701908454963590	8.6151040488975852	4.7500102358029048	3.3396729544676069	-0.2658171234699133	0.1278601362219156	
+1.3410000000000000	0.0723725945536554	8.6073543689658987	4.7198444460368894	3.1424747458975149	-0.3244241165346121	0.3091142715560625	
+1.3420000000000001	0.0533058841858660	8.6281060062874744	4.7257651117367248	3.3071368242359522	-0.0601329970072406	-0.0811347405193229	
+1.3430000000000000	0.0688457819285432	8.6490814852867608	4.6578203342490641	2.7706530388242760	0.1131397605269847	-0.0404827878851679	
+1.3440000000000001	0.0702056962215281	8.6730212754581526	4.6596018404253936	3.0775928844236198	0.0130322174135478	-0.0342151334795502	
+1.3450000000000000	0.0828419367282612	8.6547430642431955	4.6429837947220003	3.1482835905351609	0.1451603837634275	0.2980453849797909	
+1.3460000000000001	0.0736276846674201	8.6739768928707264	4.5746876271723851	3.2477815573556286	0.2016415819215693	0.0154743754782878	
+1.3470000000000000	0.0678091256524355	8.6798173756425125	4.5658690883504276	3.1254217145399257	0.0341586327383915	-0.2503809298623895	
+1.3480000000000001	0.0655857388217532	8.6936236941007010	4.5451094013956839	3.2853664924465944	-0.1285245200101352	-0.1632170450839076	
+1.3490000000000000	0.0821405979760076	8.7372178413767934	4.5061842657121263	3.5074244414602798	-0.0349193864807164	0.3014614334978012	
+1.3500000000000001	0.0664655328887915	8.7471443554691710	4.4656092164556327	3.4650724953403333	-0.1283692958854230	0.0462028420439730	
+1.3510000000000000	0.0504697706547501	8.7651290587678972	4.4397133838022063	3.2809700104582284	0.0572262524274504	-0.3040109029871071	
+1.3520000000000001	0.0685433790134167	8.7811360240714897	4.4181021862189338	3.3446270413864858	-0.1067695480606261	0.0245911881977989	
+1.3530000000000000	0.0718929820685747	8.7949078266887124	4.3915271280643733	3.2446874470280780	0.1040232970992409	0.1705689747178209	
+1.3540000000000001	0.0649796749099018	8.7989137758606937	4.3698792856431430	3.1114224764212235	-0.2440156449743896	-0.0626046207528935	
+1.3550000000000000	0.0545175696513788	8.8212221219234515	4.3437465429990656	3.3650959119506552	-0.1365745189138160	0.1726886622501247	
+1.3560000000000001	0.0747251788367495	8.8317170623481775	4.3163585218802298	3.3231146861576075	-0.0804885728309008	0.3350663312861113	
+1.3570000000000000	0.0524460238314586	8.8332330825345764	4.3018940186022832	3.2229263311523138	-0.1434870324638320	0.0085987209800593	
+1.3580000000000001	0.0304935395855707	8.8595063916053309	4.2733426102490233	3.4183631402512185	-0.2298833445975130	-0.3142054122527350	
+1.3590000000000000	0.0928436692301230	8.8426397469684126	4.2254428316661423	2.9064684211956653	-0.0687702001649894	-0.0654949818545026	
+1.3600000000000001	0.0693006646144552	8.8786446894680005	4.1969327111729822	3.3372242821856606	-0.1757171814232846	0.2292770120118230	
+1.3610000000000000	0.0645425196061645	8.8890221179074889	4.1984683960831406	3.0765215715769032	0.0996057053990765	0.2306426918434857	
+1.3620000000000001	0.0488145621174038	8.9107202768749580	4.1666656099157606	3.3502677071709059	-0.0601337640541353	0.1751309121101826	
+1.3630000000000000	0.0774819165025457	8.9171693637152476	4.0982726641403158	3.3188756743789729	-0.0619342952629755	0.1042589446860490	
+1.3640000000000001	0.0422643559601717	8.9476804863879984	4.0844781872064226	3.2106537225214486	-0.1355775396837656	0.2686955931897393	
+1.3650000000000000	0.0663255400783135	8.9529616134794257	4.0779565841932204	3.1984869610282809	0.0736897648869054	0.2104445032205911	
+1.3660000000000001	0.0784185633325273	8.9859070075370298	4.0356688556297415	3.4641902897732058	-0.0259186473224101	0.2051929747709575	
+1.3670000000000000	0.0800976430399021	8.9739669952014651	3.9999320436879384	3.1002674309772713	-0.2461769065855431	-0.0881276121871868	
+1.3680000000000001	0.0806751598537215	8.9891823815518670	3.9858896161941102	3.2182490521759148	-0.2041880680189078	0.0980741828514121	
+1.3690000000000000	0.0519660002584587	9.0048587872799093	3.9551392969502941	3.2267275388645729	-0.0814485646993499	0.0044473774496666	
+1.3700000000000001	0.0553720370027520	9.0356878223736032	3.9238222707841550	3.0703470937532140	0.1033240248615060	0.3660831370618294	
+1.3710000000000000	0.0624390281693488	9.0231214295723490	3.9164463709472828	3.2492932736248674	0.1196570769271098	0.0455424747144636	
+1.3720000000000001	0.0593332051535163	9.0486077473534898	3.8777735718418609	3.0702164781106815	-0.1480880569904531	0.0421291772322779	
+1.3730000000000000	0.0815768544217788	9.0667463806605024	3.8409008431198410	3.0539023210591290	-0.1412166989248131	-0.0781315163495229	
+1.3740000000000001	0.0679029938203572	9.0543216997165548	3.8083008363828492	3.0707301341392896	0.0268139404332080	0.1736889168639361	
+1.3750000000000000	0.0797198365212356	9.0709248176968291	3.7901063402453889	3.1815403489269336	-0.0391537975235484	0.1847634044594414	
+1.3760000000000001	0.0565786727563656	9.0596206546935889	3.7567578702471565	3.1199304264574232	-0.0494734973700084	-0.2349845314139200	
+1.3770000000000000	0.0734424683188248	9.1022218244319966	3.7180421202703755	3.3096620259871647	0.1079689688998988	-0.0140653481854663	
+1.3780000000000001	0.0732239724835284	9.1281365427027588	3.6722618907813946	3.1144021696718021	0.1794031290122428	0.0783548160155977	
+1.3790000000000000	0.0639526589854883	9.1301174642465899	3.6671368963970279	3.2706817115402806	0.0428687333714408	0.1769755026979521	
+1.3800000000000001	0.0610569030162721	9.1297833064920084	3.6182609497740468	3.2702715671698344	0.1920334320051689	0.2781213118259184	
+1.3810000000000000	0.0548907835162339	9.1389668728639410	3.6285496434182458	3.0144493200208253	-0.0207939149319254	-0.0031981111668162	
+1.3820000000000001	0.0598069100249273	9.1569487450541445	3.5864641600131670	3.1029944281029613	-0.0032796385779314	-0.1835321783167932	
+1.3830000000000000	0.0598730241068854	9.1616127553511841	3.5675309275261307	3.1693436225129181	0.2051780474175022	0.0072755604791772	
+1.3840000000000001	0.0546489443777048	9.1726689523383804	3.5487207995346353	3.1841199310469430	-0.0469774531885329	0.0578398897303944	
+1.3850000000000000	0.0638373984894949	9.1863396211081785	3.4945930337355602	3.1563622676240977	-0.1633929191757418	0.0243750262463612	
+1.3860000000000001	0.0638043509958426	9.1825981192923631	3.4554335520375719	3.1243438463924926	-0.1776205249384651	0.2990656174516400	
+1.3870000000000000	0.0625466734876469	9.1999151276446192	3.4378490882495556	3.2017275171212245	0.0953462447874548	0.1950619556357218	
+1.3880000000000001	0.0595731909938310	9.1958372572331122	3.4005769119321720	3.2216765845584643	0.0809035320045714	0.0385492028260979	
+1.3890000000000000	0.0547048214354021	9.2261963546512451	3.3746184081115431	3.3817007481794548	-0.1577990053610788	0.2686323952355763	
+1.3900000000000001	0.0723090109502132	9.2006928786974207	3.3675737055354342	3.0266564663677906	-0.1055026771835125	0.2453788798090617	
+1.3910000000000000	0.0664964324698347	9.2822379408482103	3.3431361694076842	3.0963397839915610	-0.0046015371908935	-0.1161644658496632	
+1.3920000000000001	0.0493170781892550	9.2772623696925933	3.2916209871865854	3.2743508429819710	-0.0709819047580467	-0.1268469226143431	
+1.3930000000000000	0.0934803122680574	9.2548183157158483	3.2635150070134817	3.0745708422904388	0.0609174429079325	-0.2486119394810373	
+1.3940000000000001	0.0473447393712238	9.2648002340483284	3.2344134338994781	3.3038160434265009	-0.2193707248391132	0.2542131132462021	
+1.3950000000000000	0.0561216398710990	9.2758160906942706	3.1936664456240940	3.3156790506265992	-0.1097077898306847	0.1085201870709335	
+1.3960000000000001	0.0659726428108889	9.3155254811943529	3.1887328824072352	3.2457471478899858	0.1750089539404264	-0.1794616766063744	
+1.3970000000000000	0.0742249068604392	9.3257957857767479	3.1503055327248757	3.2625600345778341	0.2869312390123344	-0.2693075976353146	
+1.3980000000000001	0.0756548807207576	9.3000663374648269	3.0974672081214703	3.3205455082367328	0.2061829624794021	0.1679780945782598	
+1.3990000000000000	0.0498805128887703	9.3381223583762445	3.0858875867941697	3.0368679670959735	-0.1219266721819200	0.3485370910241364	
+1.4000000000000001	0.0593303100518738	9.3413279883026590	3.0765870644761364	3.0438062815318800	0.2540243232648547	0.1656259305052423	
+1.4010000000000000	0.0627235194486990	9.3740297217700554	3.0181304227305401	2.9470251391042166	0.0147766069389486	0.1272319356479030	
+1.4020000000000001	0.0502201044222056	9.3532488270117149	3.0081813282528134	3.2158361030254841	-0.1209966917385478	0.2331542609218507	
+1.4030000000000000	0.0663557019629885	9.3626327205588282	2.9884643540542060	3.0072393726481947	0.0348430171023803	0.3694160598908937	
+1.4040000000000001	0.0591011958353980	9.3764387581759543	2.9477230606068443	3.3136824039300157	-0.1278168342925224	-0.1686569819448665	
+1.4050000000000000	0.0675707207647369	9.3728928406294365	2.9089068245212455	3.0205892649457140	-0.0001441111518231	0.3469811740627207	
+1.4060000000000001	0.0605669744302822	9.3723817884169094	2.8884278041297149	3.2026306518657948	0.0371766748325120	0.2173427495995077	
+1.4070000000000000	0.0509221658774133	9.4024335412516464	2.8728328951535977	3.2746472572457193	-0.2848812330281492	0.2465301073350513	
+1.4079999999999999	0.0533926874414308	9.3998935971658426	2.8292144229259457	3.0651451376799037	-0.1535254874329776	-0.1189567058696823	
+1.4090000000000000	0.0498883385616107	9.4178351535237521	2.7899933753341428	3.3437811812481724	-0.1871311032541087	-0.1897874165286025	
+1.4099999999999999	0.0660409197549748	9.4494372352270766	2.7698113828981956	3.3525457852735712	-0.0840820177464805	-0.0885321066176638	
+1.4110000000000000	0.0758354156119899	9.4570223083138067	2.7444253262072653	3.2333316931036684	-0.3350244067156574	0.0448079488452068	
+1.4119999999999999	0.0704357577523081	9.4228836009758439	2.7256858380524540	3.1439307211786049	0.1394236910986554	0.0190168728532777	
+1.4130000000000000	0.0483355228788702	9.4393212546879735	2.6830447792561030	2.9724536937893382	-0.0630727182951701	0.2658512658834285	
+1.4139999999999999	0.0825554540548629	9.4485399797566476	2.6406396813970732	3.1914971769194738	0.0067981196954199	-0.2624144217182889	
+1.4150000000000000	0.0668380246080118	9.4495811779164089	2.6227294083095485	3.1058008328841549	-0.0415493374715364	0.0998382666432468	
+1.4159999999999999	0.0874681312984119	9.4712073661438829	2.6020100194937452	3.1695470961977996	0.1788361317353425	0.0916335050320844	
+1.4170000000000000	0.0894157647800947	9.5069250584709852	2.5522279398466243	3.5340103291976015	-0.2290199664848857	-0.1062247064009889	
+1.4179999999999999	0.0672409537329366	9.4919041973182257	2.5235788404609414	3.4137978170091166	0.1188885078404188	0.1188880012111759	
+1.4190000000000000	0.0462246970786278	9.4990697030801901	2.5138089113493756	3.3005616137703280	-0.0509600654615821	0.0191913917954870	
+1.4199999999999999	0.0589015417267035	9.5339683114396703	2.4851012090325271	3.3444677665046822	-0.0009086260225234	-0.0671518100523574	
+1.4210000000000000	0.0709356932487985	9.5181444556122479	2.4316269242599846	3.1883979475008459	-0.1533812513208054	0.0560827147126211	
+1.4219999999999999	0.0456074145642261	9.5061493982704057	2.4084512697215792	3.0443624678801107	0.0845274329692222	0.1540381646980900	
+1.4230000000000000	0.0630437423441912	9.5242003489611431	2.3921663210724931	3.1295622353493031	-0.1867462712479853	-0.1723524783518230	
+1.4239999999999999	0.0676588076051517	9.5409798398201104	2.3474842232178066	2.9581063946066415	0.2863883931190727	0.1677015312552743	
+1.4250000000000000	0.0721905281446271	9.5473359214934508	2.3294677950647240	3.3053384636721765	0.1035711592611227	-0.2079128117103893	
+1.4259999999999999	0.0642356605036884	9.5449539040384703	2.2807436995672830	3.4121662929070067	-0.0630656922251857	0.0070865816081511	
+1.4270000000000000	0.0616788632290956	9.5828036189090273	2.2728053405075155	3.1543034271692760	-0.1439788125438950	-0.1466917903482961	
+1.4279999999999999	0.0553352858906354	9.5755853057109874	2.2489450578830841	3.0573744832509329	0.2947378203618444	-0.0250433847855161	
+1.4290000000000000	0.0606045364414799	9.6025623603332804	2.2066347449792310	3.2968755176416455	0.0098385234911727	-0.2918257145554234	
+1.4299999999999999	0.0545422826351720	9.5804031372790526	2.1894570923152950	3.1893927262212394	-0.0406715727938359	-0.0932903870088443	
+1.4310000000000000	0.0696612717451202	9.5948652761360691	2.1239214011883010	3.1143869140511624	-0.0480461981860879	-0.1161590282072965	
+1.4319999999999999	0.0651362804259119	9.5995418241598571	2.1188245918265318	3.0865386268546682	-0.3050404094650506	0.1098843314406997	
+1.4330000000000001	0.0664392674156366	9.6104920851370963	2.0788958574103051	3.3116219819002191	-0.0241557602701606	-0.0989321273644618	
+1.4339999999999999	0.0664608777367690	9.6186836781273275	2.0480163784258898	3.0200905849210655	-0.1787713579034586	0.3197326381243742	
+1.4350000000000001	0.0469362209959787	9.6296302529322571	2.0235871778278369	3.5116103247295691	0.1025611229068793	-0.1202717448113240	
+1.4359999999999999	0.0512730210216238	9.6270431024073488	2.0020998297789432	3.2043067277017809	-0.1438272834254528	0.0293575715958063	
+1.4370000000000001	0.0474523750010707	9.6177953927484516	1.9688665611671732	3.2530378015469261	-0.0693910594373828	0.2164025425140042	
+1.4379999999999999	0.0806137723064521	9.6322123234955530	1.9510080312101110	2.9717766336628628	0.0227125030217643	-0.1014059257239420	
+1.4390000000000001	0.0929168477646978	9.6409530843175624	1.8905227160962739	3.1015647656906173	-0.0231703473023307	0.0185064895344321	
+1.4399999999999999	0.0642254368647548	9.6413477690137572	1.8719955217846789	3.3496248984682766	-0.0528777712143024	0.1045732969739517	
+1.4410000000000001	0.0647185757714646	9.6611567651758108	1.8541027748123557	3.2198411744680224	-0.0467623003973244	0.2019831527477012	
+1.4419999999999999	0.0553860414768165	9.6593917101165605	1.8173716208484825	3.2560966269732203	0.1788531698935811	0.0859192812471827	
+1.4430000000000001	0.0756616272062051	9.6730365006384602	1.7906720391081385	3.1330732182126342	-0.0720871938951431	-0.1105145106142853	
+1.4440000000000000	0.0935150075365842	9.6485440872943222	1.7713647216910200	3.2255625291509422	-0.1393710855986098	-0.0351973182846617	
+1.4450000000000001	0.0712345540107601	9.6824507973184630	1.6928038852738490	3.2463555707503975	0.0563844048207498	0.0800898814329839	
+1.4460000000000000	0.0534271389465628	9.6700520044390466	1.7239163194441001	3.2396942972675733	-0.1516147108887261	-0.0780213141932610	
+1.4470000000000001	0.0645927552746028	9.6705107483738093	1.6748574592209251	3.2349708178570293	-0.0008954584268217	0.2133727455254998	
+1.4480000000000000	0.0624815383132473	9.7037907882858381	1.6329810698667837	2.9978944360633069	0.0139859764113759	0.2963219350134608	
+1.4490000000000001	0.0696894100207187	9.7113808704792284	1.5856730738667650	3.4609634670786802	0.0874585410619036	-0.1523906494967774	
+1.4500000000000000	0.0858464201621822	9.6872386294682631	1.5492068327620359	3.0724154143001599	-0.0955566120521474	0.1796804153347326	
+1.4510000000000001	0.0826526516377391	9.6966158419684554	1.5489548243496640	3.3429919749014858	-0.1621753999405639	0.1307018654446203	
+1.4520000000000000	0.0550850688386374	9.7067514488216506	1.5167266873302032	3.0809630885960795	0.1196541690782691	0.0710514671566434	
+1.4530000000000001	0.0535370827364915	9.7253212815958747	1.4691304281147386	3.2224617261174768	-0.1927934609224955	0.0755060756026463	
+1.4540000000000000	0.0692411993418768	9.7124264011392683	1.4472666727763566	3.0301257525370806	-0.0773515435681586	-0.2105862927271652	
+1.4550000000000001	0.0964555472846629	9.7006977106285373	1.3879052899913997	3.1252734730276033	0.0571776042506664	0.0666391317151574	
+1.4560000000000000	0.0698798570742002	9.7219717736931326	1.3983826094205334	2.9748157062831169	-0.0034690038010306	0.0543039773613534	
+1.4570000000000001	0.0823331763361198	9.7335324777698773	1.3448288991822217	3.2047738844565288	-0.3420252596348311	0.0074134484616842	
+1.4580000000000000	0.0501461047878965	9.7437001113553539	1.3464814798327884	2.9397301524522810	-0.2111035596782759	0.1672298094793041	
+1.4590000000000001	0.0690226324745502	9.7620496278135906	1.3125632434792733	3.0998321847816230	0.3686697843104983	0.1331885526968863	
+1.4600000000000000	0.0730998182504554	9.7512659267940744	1.2717218534682972	3.1613413509764641	0.0520467023687341	0.1742910076533896	
+1.4610000000000001	0.0556750215006776	9.7215454437135218	1.2352281484492278	2.9214986295811460	0.0998270255036873	0.1210747684586774	
+1.4620000000000000	0.0669440627809455	9.7674312943507857	1.2054386298341622	3.0182926351939008	-0.0390054344760701	-0.0199091806038492	
+1.4630000000000001	0.0498593642534468	9.7378130333283757	1.1610136775096447	2.9509319768694513	0.1609632063299421	-0.0299886080702713	
+1.4640000000000000	0.0548132282333684	9.7647981168755180	1.1319474023767770	3.0302458768327187	0.1392518177942349	0.0727831564101040	
+1.4650000000000001	0.0522026183706385	9.7512962358505675	1.1270009254126980	3.1156092287313748	0.2327802579371130	0.0350574207384883	
+1.4660000000000000	0.0722745667688290	9.7687093468035897	1.0957350245931394	3.0952524741412648	-0.1847195942060214	0.0819053079160265	
+1.4670000000000001	0.0631411824681947	9.7689989200745782	1.0493765431814219	3.5044897978121705	0.2995959907645161	0.1646358147349970	
+1.4680000000000000	0.0797889708579951	9.7639506789292625	1.0085065782171567	3.2414242243401508	-0.2305649889241902	0.1077300238521550	
+1.4690000000000001	0.0586713061110156	9.7744012961440898	0.9986901861678062	3.1713399740429566	0.1919422057520589	0.2247213638908991	
+1.4700000000000000	0.0789734646800811	9.7636967645545862	0.9480446543648239	3.2868016341121744	-0.0012850656062499	0.0304107586942169	
+1.4710000000000001	0.0824576177296071	9.7892757545534437	0.9484174690045359	3.2562177573196824	-0.1011242210280772	0.1604907462013069	
+1.4720000000000000	0.0589979021184228	9.7861062159526551	0.8936304624885522	3.4823844846882981	-0.1903801617275586	0.1429573596358414	
+1.4730000000000001	0.0494347839632551	9.8009573003863935	0.8714587353473439	3.3128064668374342	-0.2754229935495419	0.3809033789861705	
+1.4740000000000000	0.0523693572877594	9.7908314592522689	0.8511364788212328	3.5277727379641113	-0.0468509633607012	0.1754265592470897	
+1.4750000000000001	0.0555505574365804	9.8067828575386002	0.8235614201583504	3.0240546327861755	-0.0868058245948853	0.2298202990814247	
+1.4760000000000000	0.0582998658146056	9.7940103662332962	0.7735331595075932	3.2750901825901453	0.0534511044326041	0.0421486687496443	
+1.4770000000000001	0.0684050534305472	9.8103627827241322	0.7473145387759758	3.1197159089955755	-0.0786426194217651	-0.0976149414886895	
+1.4780000000000000	0.0709746534066881	9.7954455393938566	0.6903213664479630	3.2982277116298038	0.0653273558227738	0.3210730399284802	
+1.4790000000000001	0.0523939623112956	9.8025712772773641	0.6765840959932901	3.2742014076062644	0.2166639632015918	-0.0828729286951609	
+1.4800000000000000	0.0684440430776003	9.8218517879029186	0.6498507620741674	3.0527260470769373	-0.1543837097728072	0.3003137953004083	
+1.4810000000000001	0.0576938768941712	9.8107663841475166	0.6138384087319301	3.3718809444759130	-0.2269505547621195	-0.0906898161493667	
+1.4820000000000000	0.0834172060208600	9.8111981788270537	0.5817222983636368	2.9514986885641470	0.0035488397628474	0.0495217060471989	
+1.4830000000000001	0.0854898055490845	9.8086916763412155	0.5713571454709058	3.0553710497485471	-0.1874407468750068	0.2040338058007505	
+1.4840000000000000	0.0606121820696403	9.8179242161294802	0.5297464927131866	3.2771015323456711	0.1508861982349370	-0.1644493098220896	
+1.4850000000000001	0.0874179242834072	9.8060758615101307	0.4785290487587091	3.0728459180658927	0.2637510713074983	-0.2539508666492729	
+1.4860000000000000	0.0571187440948143	9.7980277916851968	0.4550123113772850	3.2559820927244316	-0.0034759420595399	0.1263402888320624	
+1.4870000000000001	0.0567994927801912	9.8348483071667587	0.4248531144955345	3.6224705038210159	0.1391909227267157	0.2457579727898186	
+1.4880000000000000	0.0671117822577663	9.8152610138536360	0.4131243996127419	3.2976331510270023	-0.0776239130078054	-0.0751296994270789	
+1.4890000000000001	0.0816595808161660	9.8124931776313211	0.3896375175237732	3.2838450884849562	-0.0516025038375338	-0.0505335313406933	
+1.4900000000000000	0.0668114492185304	9.8082759806879150	0.3223741758463272	3.4949715828951398	-0.0011266167520665	0.1552834615139160	
+1.4910000000000001	0.0599244739284112	9.8147418394928145	0.2933855537877792	3.2548103495011000	0.1135431155665415	0.2247828395360648	
+1.4920000000000000	0.0715245919966305	9.8281819936232626	0.2824111998573642	3.2503299232712388	-0.2388074728611853	0.1530335577908258	
+1.4930000000000001	0.0878651860951902	9.8133820275871155	0.2638954719796616	3.4043129454414904	-0.0456586875306264	-0.2323831705120363	
+1.4940000000000000	0.0980537299221329	9.8315291398558706	0.2275629087714155	3.2836725104819529	-0.0663954710485600	0.0239759276248127	
+1.4950000000000001	0.0740852701069821	9.8519332320544759	0.1711658722814433	3.1977390360715612	0.3098974396799589	-0.0045125481068224	
+1.4960000000000000	0.0468355463013057	9.8344369003637837	0.1597639101718631	3.0324508595077684	0.0545764054874505	-0.1094523317749418	
+1.4970000000000001	0.0770760666480980	9.8241784519209467	0.1310211384414054	3.1416809411800859	-0.0721497619516098	-0.1358030643401087	
+1.4980000000000000	0.0742581668562001	9.8254364783311576	0.0869594021085225	3.1371363064685380	0.0733961036899759	0.3625555802693564	
+1.4990000000000001	0.0721103798964793	9.8065694042839500	0.0550300357435650	3.0366259030461813	0.0776504777171948	-0.0976726322965003	
+1.5000000000000000	0.0627931595267166	9.8497690978076413	0.0269320916941039	-0.1650066252953180	-0.1420421588402446	0.2561616386344335	
+1.5010000000000001	0.0706115655506071	9.8299664732948688	0.0320634990444278	0.1484790266213564	0.2152972357006943	-0.0245575513514965	
+1.5020000000000000	0.0526164741918265	9.8288612166698890	0.0400812370481560	-0.2714502507967241	0.1138495639061051	0.1291473320187013	
+1.5030000000000001	0.0918238651761452	9.8169030798660391	0.0294345937175002	0.0519786913493353	-0.1159304205868731	0.1652923692575997	
+1.5040000000000000	0.0646841734278643	9.8324490849745878	0.0408845676587569	-0.0593876593640561	-0.1654851540025659	0.3220562882673170	
+1.5050000000000001	0.0819460691544183	9.8367661534564412	0.0327592411139550	0.4974325518206789	-0.0751041598766831	0.0100382157133084	
+1.5060000000000000	0.0665976077680151	9.8369713162034902	0.0293987562000069	-0.1587221260760542	-0.0266941148283389	0.3706787320877261	
+1.5070000000000001	0.0661678271490552	9.8270468256720349	0.0172683072001369	0.2812955238580855	0.0263595994571108	-0.1140443074288125	
+1.5080000000000000	0.0822881329276327	9.8315244314379626	0.0445230117204060	0.0381910019591522	0.0069840673115773	0.0640778809712134	
+1.5090000000000001	0.0989765147588256	9.8325363363625531	0.0383782275430190	0.2276935402988575	0.0729061948902499	0.2393602563395930	
+1.5100000000000000	0.0539514474260031	9.8244320624728712	0.0551752054038522	0.1398822823186985	-0.1109313326082615	-0.0591915439073332	
+1.5110000000000001	0.0675236591404252	9.8094318512019019	0.0219519742470458	0.2276600783088029	-0.2259893567841914	0.1836697849911202	
+1.5120000000000000	0.0916706143448702	9.8322945080725663	0.0389733686859890	0.0400850590088256	0.0064825502166456	0.3128045279481722	
+1.5130000000000001	0.0588304892881989	9.8126048844021554	0.0506993424892410	0.2943667255031976	-0.0294733345213423	0.0005460229053137	
+1.5140000000000000	0.0476943876308950	9.8262878339126534	0.0288766523440964	-0.2246269732398865	0.0273979368506370	0.2365720132682327	
+1.5150000000000001	0.0503658260806534	9.8402932852048721	0.0378516841682729	0.2592563398186851	0.0426446173771653	0.1622872955274919	
+1.5160000000000000	0.0660636323364018	9.8256813945852830	0.0330952359403602	0.0216129204177095	-0.1720915520271474	0.0444541190463430	
+1.5170000000000001	0.0588161537684971	9.8242617361106159	0.0337857143693628	-0.0244830365820152	-0.0568616478625648	0.1475108448691674	
+1.5180000000000000	0.0725316756872550	9.8140293149514886	0.0408546255578660	0.0415736005905527	-0.3864809890185154	-0.0009946343519484	
+1.5190000000000001	0.0662256630025533	9.8281676810061853	0.0290181610869718	-0.0102012736096332	-0.0058325532133801	0.0361186529460593	
+1.5200000000000000	0.0563593824301514	9.8343062747035432	0.0305375641686922	-0.0490831304786379	0.2002755733448024	0.0753801286065664	
+1.5210000000000001	0.0508981836382907	9.8311331426444735	0.0360716764746191	0.0648822077561563	0.0076522371201656	0.0273284091369329	
+1.5220000000000000	0.0620566529890984	9.8229142528097295	0.0413013087052475	0.0430427304766684	-0.2096308843596638	0.1286418028249096	
+1.5230000000000001	0.0595330349288822	9.8252252969967788	0.0382517644348631	0.3075711984719320	0.0910092481160477	0.1071129940791341	
+1.5240000000000000	0.0640814029027433	9.8362048348427926	0.0328217466987527	0.3472231415837117	0.0461841003714029	0.0547376865247390	
+1.5250000000000001	0.0696951824270559	9.8283318153501167	0.0423080108310572	-0.0810059413330776	-0.1123725544021838	0.1096899177331938	
+1.5260000000000000	0.0499099787549243	9.8375621841695420	0.0454271230871884	0.0425255563445426	0.2386023404281269	0.3186782648947969	
+1.5270000000000001	0.0555789929919921	9.8094641560339912	0.0347800372143070	-0.0549392561909560	0.0078582193368376	0.0889089383442336	
+1.5280000000000000	0.0799491173681870	9.8049314445167006	0.0359146527609319	-0.1250595775747556	-0.1083713985368654	0.0218471986452734	
+1.5290000000000001	0.0589909471272826	9.8111636288532988	0.0404366028999373	0.2514931442106794	-0.0128607799671012	0.2285904047146681	
+1.5300000000000000	0.0383450024996222	9.8293673897125799	0.0353125640585492	0.2708041438726498	0.1739839855728815	-0.0093696769346407	
+1.5310000000000001	0.0728629852481223	9.8292150344877722	0.0241978461068899	-0.0143749078926034	-0.0234512467198485	-0.0207444005625812	
+1.5320000000000000	0.0772609978097328	9.8152000030002196	0.0381805811002695	0.1422806649812145	0.0407867690767212	0.3995669473188483	
+1.5330000000000001	0.0768230684903860	9.8152860121731802	0.0419444045502362	0.1589352092741148	-0.1156340144511899	-0.2176061611218017	
+1.5340000000000000	0.0872439568011626	9.8387727466721806	0.0139673109757966	0.1958637229542762	-0.0274514329190068	-0.0179200897344955	
+1.5350000000000001	0.0548191859310187	9.8203516672908915	0.0327564373603072	0.1609704349148938	0.0688733563194858	0.0264329314191488	
+1.5360000000000000	0.0545686569115209	9.8085316834669527	0.0336944114058716	-0.0594485159733591	0.1596083508024741	0.1030003236605253	
+1.5369999999999999	0.0611779076307018	9.8132057422961392	0.0107263059479442	0.1586442662021386	0.2480716587239373	-0.0757280133357189	
+1.5380000000000000	0.0479437206895238	9.8080088640732797	0.0365788096092564	-0.0305289197812165	-0.1496540376894574	0.1316207122135653	
+1.5389999999999999	0.0805714655335094	9.8112808437791763	0.0550940776014433	0.3302370437052192	0.1290570895449310	0.0726409117713001	
+1.5400000000000000	0.0480367197987367	9.8025149971253285	0.0368634689920081	0.0571231331915218	-0.0204147856223035	-0.0472575500570274	
+1.5409999999999999	0.0410081850660942	9.8065091762014891	0.0399152798695960	0.0271050796019484	-0.0438002003959840	-0.0614893726106868	
+1.5420000000000000	0.0616503899695050	9.8258112124049610	0.0313367080784413	-0.1301253154181347	0.0478746147504689	0.2371844271074307	
+1.5429999999999999	0.0644252234863658	9.8232869257465563	0.0499615322066273	-0.0473927965504706	0.0247130531060548	0.2282434704996746	
+1.5440000000000000	0.0645521797242768	9.8159455375978819	0.0498063798341898	0.0874193434116400	-0.0712810727045307	-0.1314015925347140	
+1.5449999999999999	0.0375110164541434	9.8318873573346046	0.0597447935741212	0.1549441475129846	0.0195639403211826	-0.2455692808039555	
+1.5460000000000000	0.0698012284775414	9.8307222579349354	0.0403894285774658	0.0721769242551729	-0.2508115677224255	0.2214062990261551	
+1.5469999999999999	0.0893097610591121	9.8324230675827042	0.0317479692744418	0.1345210648011191	0.1251460342700587	0.1063402361256047	
+1.5480000000000000	0.0536730911573374	9.8220448553036981	0.0221373274712204	0.0268093806532996	0.0545609251115207	0.0542100306169965	
+1.5489999999999999	0.0837600966357890	9.8256199508790107	0.0160373950847493	-0.1063573063122295	0.0176996819268019	-0.0699044040225460	
+1.5500000000000000	0.0584506757174125	9.8565871173300685	0.0317168340040040	0.0504955653326894	-0.1406157127674407	-0.0232573023209038	
+1.5509999999999999	0.0892831372753701	9.8097358801722301	0.0517549851050829	0.1169868546744433	0.1404712696361620	-0.0389237592047755	
+1.5520000000000000	0.0696049450628867	9.8074967800692292	0.0336089974589167	-0.1352335806326068	-0.0792008356943095	-0.0317516676854431	
+1.5529999999999999	0.0620107648281523	9.8211918142894721	0.0460807310587556	0.1249170125527753	0.0549386192383759	0.0739793104285449	
+1.5540000000000000	0.0665612774432851	9.8056939402154839	0.0274849269731984	-0.0763642339755373	0.2367677185566428	0.1153573889736911	
+1.5549999999999999	0.0836009331264685	9.8472412670685063	0.0421733642286076	0.0263800230912585	-0.0068849613663059	0.1323960910872459	
+1.5560000000000000	0.0748795997549740	9.8308677749893754	0.0448462442935576	-0.0024112559362959	-0.0729429140638035	0.0126610969506148	
+1.5569999999999999	0.0548784234316798	9.8243964498880558	0.0668097589904303	-0.2111794320128042	-0.0465932426308575	0.1819156249412238	
+1.5580000000000001	0.0611200178512250	9.8233519218083032	0.0226113824354027	0.0250776050474457	0.1164962563729243	0.1066188451232286	
+1.5589999999999999	0.0562216219393686	9.8405232267271021	0.0324473900000325	0.0269090740475183	-0.0654359255763930	-0.0310609937111270	
+1.5600000000000001	0.0721871403587802	9.8253558331744468	0.0452679000521527	-0.1035826625897882	-0.1006545985345818	0.2302046906296891	
+1.5609999999999999	0.0718751908767206	9.8170272327633388	0.0263373763481005	0.1236602538574074	0.1115816862372049	0.2697975055237347	
+1.5620000000000001	0.0429383405475114	9.8479699250734729	0.0237083974719735	-0.0180204410964864	-0.1688804063940291	0.4156254066641912	
+1.5629999999999999	0.1025643172173321	9.8340112732933953	0.0372282971998721	0.1811455183471717	0.0031890623787898	0.0594510053804223	
+1.5640000000000001	0.0556123332151520	9.8265771108967872	0.0543027145494219	0.0594354450076680	-0.2694409151077496	0.0341616941794394	
+1.5649999999999999	0.0819803291779365	9.8311067144521722	0.0346798263624039	0.3109499398674612	0.1532290516529323	-0.1009729351114696	
+1.5660000000000001	0.0765631135774066	9.8456470167528938	0.0378440534708883	0.2809906723849636	0.0169126415804037	0.0086859963937474	
+1.5669999999999999	0.0701573367000520	9.8232378904066984	0.0380020597295524	0.1667036216987846	0.0588980344689823	-0.1420896202207066	
+1.5680000000000001	0.0695233928955483	9.8429016175508135	0.0174800967378198	-0.0226568900931726	-0.0089071379471262	0.1418650047863345	
+1.5690000000000000	0.0534570101680617	9.8107093326835351	0.0187109171873381	-0.0377106779015419	-0.1689232568018944	-0.0941239954217166	
+1.5700000000000001	0.0649309621428000	9.8238920423431999	0.0327907823675472	0.0067013745525548	-0.1639298453129039	0.1818884474578500	
+1.5710000000000000	0.0649200019642898	9.8388825470187431	0.0359270221210521	-0.0287185854146124	-0.2878695274058233	-0.0078910859591226	
+1.5720000000000001	0.0826755365531131	9.8322067404688713	0.0009350738259655	-0.0775475243558904	0.0331316626526724	-0.1290055741128904	
+1.5730000000000000	0.0469658049138992	9.8131207631965047	0.0496418064822471	0.1137503876050004	0.0258183047934430	0.1559974869198295	
+1.5740000000000001	0.0716186701568350	9.8084335628975943	0.0416144889423349	0.3686857620026465	-0.1979679442752365	0.3525772551155972	
+1.5750000000000000	0.0612350167573772	9.8337333901563113	0.0355323722646536	-0.2519232895540279	-0.2124929755240484	0.0194945007030394	
+1.5760000000000001	0.0617760451955385	9.8186064930047863	0.0355719590410301	0.3182753027209988	-0.0225000434639469	0.2904729478004688	
+1.5770000000000000	0.0877056611240021	9.8434303553270848	0.0354070948435111	-0.0098670373622974	0.0189738297009543	0.3303076564953795	
+1.5780000000000001	0.0790114442935893	9.8105378129971665	0.0596074790392966	-0.0686268169708076	-0.1658205860144197	0.0833712235191844	
+1.5790000000000000	0.0668598881717273	9.8450947633394108	0.0207992001168359	0.1268291288688031	-0.0268520580518168	0.1764059562453878	
+1.5800000000000001	0.0616840024089567	9.8295337072464246	0.0115704869126066	-0.0094074350554008	-0.1401397203115001	-0.0951350060711788	
+1.5810000000000000	0.0739496710498933	9.8486727768504263	0.0203551558496436	-0.1261738345443686	-0.0638811272318321	-0.0750263586055929	
+1.5820000000000001	0.0644050223812932	9.8054180434449805	0.0429243149445861	0.0023254934360916	-0.0164662251937925	0.1162940092963119	
+1.5830000000000000	0.0655527761696269	9.8256749183050047	0.0519024974387638	0.1408132995988004	0.1327048445389829	0.2391842269516287	
+1.5840000000000001	0.0436447529871471	9.8232205180624046	0.0345925869785143	0.1234730461585181	-0.3946952910272010	0.1978719432252153	
+1.5850000000000000	0.0645873558888413	9.8130500261329558	0.0436239763958535	-0.3076146823690032	0.3256083349824110	0.1632134179494371	
+1.5860000000000001	0.0502573955918875	9.8279373716537641	0.0398763244097438	-0.0960999799407461	-0.1279825377186271	0.0312768024553238	
+1.5870000000000000	0.0631029788915366	9.8204695078611532	0.0429530722809357	0.0196810839974169	-0.2785971317957242	-0.0540600335709659	
+1.5880000000000001	0.0582516905378079	9.8126850467197944	0.0479019372334776	0.0956930846827526	-0.1413494968620516	0.1221893025010024	
+1.5890000000000000	0.0791351201122055	9.8216959489055924	0.0461531713277994	-0.0867769318843652	0.1596440567061113	0.0055478195330985	
+1.5900000000000001	0.0571440870266752	9.8361980274478586	0.0471510427422108	0.1040732166781589	-0.1081827346736311	0.1026724390839403	
+1.5910000000000000	0.0406539430779291	9.8413617404742215	0.0451438555655140	-0.1066678511941710	0.0784707510267546	0.3288803252410168	
+1.5920000000000001	0.0465805670507190	9.8269570608478407	0.0439582294090820	-0.2333254399218183	0.0760703053197758	-0.0756720457726510	
+1.5930000000000000	0.0941478762517581	9.8252878288525647	0.0384418068713006	0.2041553547705081	0.2084649369679670	0.1859644710980151	
+1.5940000000000001	0.0499495947933934	9.8027237851776636	0.0310583758196765	0.0695913686118121	-0.3049252734815657	0.0520688808050553	
+1.5950000000000000	0.0721530443429949	9.8030633226390691	0.0253789856540291	0.0053786976423876	0.2478565204832312	0.3227907295742402	
+1.5960000000000001	0.0747310904379462	9.8370262531737822	0.0267079668804491	-0.1452418225530003	-0.0081240093467424	-0.2174376837466603	
+1.5970000000000000	0.0488409523590535	9.8486901132216662	0.0396615281314432	-0.0057655864604495	-0.1946734733086469	0.1020192258671643	
+1.5980000000000001	0.0588788038386284	9.8364763848581696	0.0378354352176262	-0.0840155532716068	-0.0361577154274208	0.1598104052706611	
+1.5990000000000000	0.0997154959249334	9.8178918417107131	0.0135667061766103	0.1486390150784511	-0.2001497778599806	0.1868070624242200	
+1.6000000000000001	0.0686148754907823	9.8142645991362532	0.0342166645362754	0.1804867018076318	-0.0264886413735826	0.0304714153167801	
+1.6010000000000000	0.0756944873087511	9.8353741494753510	0.0410974975990167	0.1925802561509898	0.0208587441118171	-0.0227657639419121	
+1.6020000000000001	0.0610367449870674	9.8121289788836155	0.0512151319410739	-0.1207366160037716	0.0199292504030956	-0.1142497340609540	
+1.6030000000000000	0.0604577621467809	9.8121365064106580	0.0385934070010969	-0.1144444410559386	-0.0924123203525431	0.0833110250153631	
+1.6040000000000001	0.0783951366569593	9.8258234541956266	0.0434256895320778	-0.1181910264486049	-0.0253006700929148	0.0294362699855002	
+1.6050000000000000	0.0633476461253015	9.8196274558922152	0.0186973565787260	0.1616724504926904	-0.0363951049480477	-0.0030768854719261	
+1.6060000000000001	0.0733950215418834	9.8224378994870580	0.0744590144001969	0.1730709525121258	-0.2855581900379995	0.2975381856516918	
+1.6070000000000000	0.0778873244912095	9.8322692870879695	0.0442320250427475	0.2761333120923044	0.0321986744766452	0.3000948087865293	
+1.6080000000000001	0.0620783402817025	9.8170311929136762	0.0276399987600643	0.0368068213329611	-0.0624122141501060	0.1702246565938663	
+1.6090000000000000	0.0724463118634133	9.8271177131625027	0.0355962640332593	-0.2034988615308437	0.0480725733959091	0.1607796048266084	
+1.6100000000000001	0.0777218940364314	9.8174705299876397	0.0482271036318827	0.1510376107660171	-0.0442576795288381	-0.0291283879008467	
+1.6110000000000000	0.0646616527434647	9.8329703600832588	0.0391847723251759	0.2070824881792369	-0.2616244000737082	-0.0534198820540771	
+1.6120000000000001	0.0716052297492316	9.8550449475284054	0.0395769111189918	0.1281457871295578	0.2416909437099805	0.1242548729814962	
+1.6130000000000000	0.0618448599811075	9.8549765792188104	0.0406880461468732	-0.0543499906072687	-0.2317742745858514	-0.1369544196364137	
+1.6140000000000001	0.0720678221386913	9.8202386244073718	0.0242856729086037	0.1019092306570173	-0.1223542685332750	-0.1883208165893445	
+1.6150000000000000	0.0703348946495267	9.8356548488395852	0.0349331324237573	-0.0579004438373620	0.0354214051586722	0.2090087913613761	
+1.6160000000000001	0.0582144801429900	9.8429496348213128	0.0260072748795437	-0.0029690817389757	0.1782136879614898	0.2739530540536135	
+1.6170000000000000	0.0426783989134209	9.8275283026361890	0.0503295367192460	-0.1114302322461925	-0.1297141991086393	0.2951519467995357	
+1.6180000000000001	0.0783930202756341	9.8350394115459707	0.0289078636144427	-0.0831166192884938	-0.0861363654386748	0.3213158863643341	
+1.6190000000000000	0.0734963630554046	9.8175745034070658	0.0248846027543105	-0.0972167080027958	-0.1160849404465244	0.2219150512565093	
+1.6200000000000001	0.0596073983606588	9.8356012956020660	0.0469251074312136	0.3412157920214540	-0.1405013351156553	0.2293288620636669	
+1.6210000000000000	0.0657316377404245	9.8222087402552027	0.0253432962704588	-0.0806206528342503	-0.1459310522896102	0.1387665536223881	
+1.6220000000000001	0.0663864792637582	9.8272069182293436	0.0469438229317739	0.1162875647440752	0.1970859535281464	-0.0319849156077158	
+1.6230000000000000	0.0619350275438317	9.8227109604851552	0.0415133013910122	-0.0481579589114381	-0.2305791939141206	-0.2208820969916640	
+1.6240000000000001	0.0647101053800098	9.8358557788972441	0.0315931210791999	0.1213200913507118	-0.1599977334091524	0.4139569159706786	
+1.6250000000000000	0.0767388905735051	9.8376831911727614	0.0365900587718495	0.1752459299513293	-0.2112315431498574	0.1427705337501117	
+1.6260000000000001	0.0348325399812936	9.8118917336603833	0.0412581184358060	0.3586474704282741	-0.0174508277964495	0.1426430770289601	
+1.6270000000000000	0.0611439438725042	9.8206884232695906	0.0349435275241546	0.0107627847762139	0.2368330923798610	0.0060609919740321	
+1.6280000000000001	0.0510955343717436	9.8191841724193836	0.0422228313582532	0.2532341192267077	-0.1020087061975623	0.0630504817798880	
+1.6290000000000000	0.0753094646176159	9.8026334875697607	0.0491896869583660	0.1090669406857771	-0.1880592233583240	0.0066637740932382	
+1.6300000000000001	0.0674551077408149	9.8417024877970949	0.0481645481889417	-0.1251956530135105	-0.0730487560031923	0.1725016295118048	
+1.6310000000000000	0.0602535715100974	9.8247402773810553	0.0195468506689084	0.2514707040154535	0.0007500247894674	-0.0206302883408661	
+1.6320000000000001	0.0548255978716947	9.8289260852457403	0.0461806074029059	0.0854523667688485	-0.1053992829963013	0.0495456701676247	
+1.6330000000000000	0.0893615215481464	9.8215516749072798	0.0464809971359176	-0.0999299562845424	0.0834209207558606	0.0118078901272683	
+1.6340000000000001	0.0799654839214166	9.8167535644401038	0.0246703883812468	-0.1126482831676015	0.1451867255416931	0.2960568891726208	
+1.6350000000000000	0.0641558183671414	9.8194186585744490	0.0179909437713409	0.1842999672485791	-0.1675238705619496	0.3012019473660803	
+1.6360000000000001	0.0674337334835761	9.8407542238724428	0.0504626437731922	0.3935639281467983	0.1858484962492349	0.1022940558365933	
+1.6370000000000000	0.0592585167296468	9.8184765444465931	0.0565252253637932	0.1378621284914253	-0.2391535863934055	0.2151420871431041	
+1.6380000000000001	0.0701878821603011	9.8280173185386293	0.0216816534350629	0.0522519233154562	-0.0194250777978654	0.3180845748381598	
+1.6390000000000000	0.0766449477959985	9.8198299475438162	0.0244909665694371	-0.1678360051429547	-0.2130818671848685	0.0260399309551885	
+1.6400000000000001	0.0601456990841867	9.8353751530273872	0.0394706173702528	0.1733171571232035	-0.2013082863063965	0.0058268453866926	
+1.6410000000000000	0.0823146918316014	9.8360282841846232	0.0582517533074625	0.1182298938938312	0.1420892381544100	0.1454653985016593	
+1.6420000000000001	0.0675217979109444	9.8229359334481323	0.0366146265660114	0.0866270828804553	-0.0873671828280897	0.3847766007893612	
+1.6430000000000000	0.0532678475483733	9.8285726798625692	0.0362857501894892	0.1286367641552976	0.1224349378326565	0.1524849146462319	
+1.6440000000000001	0.0542930411892241	9.8233071606580005	0.0302516640106969	-0.0270691309295684	-0.2129498168854568	-0.0556487563233992	
+1.6450000000000000	0.0630484760554118	9.8267518608484181	0.0413201478149091	0.3124874860939019	-0.1808651722002197	0.0337417371545911	
+1.6460000000000001	0.0797280883090445	9.8202694960696011	0.0295530628420434	0.2781214786906548	0.0498013506588938	-0.0336650249460570	
+1.6470000000000000	0.0351863616922098	9.8094194244182678	0.0535976597523618	0.0519896233189048	-0.1203135877414412	0.1353921643186423	
+1.6480000000000001	0.0664434714403879	9.8225812401165609	0.0606518668275444	-0.0521097481853507	-0.3063896001799620	0.0139387421271268	
+1.6490000000000000	0.0725887497695204	9.8321454269916977	0.0280331466964311	0.2407949892336952	0.1692523783358173	0.1498794430942931	
+1.6500000000000001	0.0581544456756516	9.8418362131915895	0.0398413178566376	0.1845771537837855	-0.0717586345442494	0.0733131101162649	
+1.6510000000000000	0.0756296633108182	9.8291647892660574	0.0328775248483821	-0.0978481837830517	-0.3262644255626326	-0.2388103503086254	
+1.6520000000000001	0.0403578276509465	9.8208150468371755	0.0462849711300602	-0.0302829028290110	-0.1514960850268287	0.0316348226145058	
+1.6530000000000000	0.0747148710426243	9.8144840697793878	0.0256239482920645	-0.0709238523214647	0.0330841000812267	0.1767253745851138	
+1.6540000000000001	0.0630077544003580	9.8043468871625148	0.0393419367488268	0.0529481741048947	0.0204403549723432	0.1998887381573180	
+1.6550000000000000	0.0726460168787628	9.8492269582510001	0.0422999873071430	-0.0573799923647212	-0.2330918205844572	0.1413591775336473	
+1.6560000000000001	0.0672462210519432	9.8408032525356965	0.0493224895189039	0.0621511170762664	-0.0834325386971087	0.1856125827613568	
+1.6570000000000000	0.0413573701726235	9.8230589496711627	0.0301289117171725	-0.1647159647940499	0.1982378690364570	0.0653999674180568	
+1.6580000000000001	0.0598148456962372	9.8186013581358900	0.0448276770797492	0.1648134627936246	0.0083068470457422	0.1001857150720470	
+1.6590000000000000	0.0510288987043202	9.8289445369931450	0.0504150405119594	-0.0538495670099030	0.0861192710387597	0.2360510604350403	
+1.6600000000000001	0.0670681693902811	9.8276270971318578	0.0476116537147461	0.0146195915112498	0.0933789371487791	0.2394104268371471	
+1.6610000000000000	0.0726564340783773	9.8258693092750242	0.0541069543414659	0.1036630670399116	-0.2596231571544579	0.1422572821163738	
+1.6620000000000001	0.0695918858580596	9.8177102313614260	0.0196209115321283	-0.0528056107086522	-0.3308258714778973	0.0649504721333375	
+1.6630000000000000	0.0604907270969109	9.8084729537684741	0.0160655992084774	-0.0005111671464549	0.0841604484182472	0.1604962976809192	
+1.6640000000000001	0.0619596722042845	9.8459816895121346	0.0256311908242944	0.1192141490164692	-0.1548542986417613	0.1367766101697147	
+1.6650000000000000	0.0433251646803012	9.8471345236660888	0.0340927622443828	0.2016102866513932	-0.0917190105287130	-0.0449515437571714	
+1.6659999999999999	0.0597149865021090	9.8259294649585875	0.0471046061167523	0.0532215430417609	0.1151580643844019	0.2154826757134751	
+1.6670000000000000	0.0688262336586880	9.8380548883671093	0.0547154994750547	-0.1843088008498740	-0.1514992837928647	0.0187277013981260	
+1.6679999999999999	0.0367349414044161	9.8200768648905790	0.0494075062086684	0.1702064725846044	-0.1157654500075081	0.1214898293022115	
+1.6690000000000000	0.0633315194879043	9.8076737048992904	0.0537842408994724	0.1795022826119630	0.0372907751480064	-0.1751194015833627	
+1.6699999999999999	0.0456790382941772	9.8155638628359316	0.0368401278656836	-0.0918786724073399	-0.1570981940934859	-0.2274648969039139	
+1.6710000000000000	0.0706010207602461	9.8229255876506052	0.0191753020012609	0.2335904384689293	-0.0698823517306076	-0.0547953406906598	
+1.6719999999999999	0.0545454835565058	9.8346650360880421	0.0448523616946680	0.1526931271374253	-0.1369693797317841	-0.1182477633853457	
+1.6730000000000000	0.0546033040638554	9.8340150899606069	0.0324690416181684	0.0732555563327269	-0.0549934692649461	0.2678706732785975	
+1.6739999999999999	0.0659996561460027	9.8332549591996141	0.0493802943381047	-0.0338839263463251	0.0922680591885599	0.0846505315796057	
+1.6750000000000000	0.0526078919056681	9.8180354591189651	0.0604771225218866	0.1991251006574534	0.0642246302346816	0.1649972158901610	
+1.6759999999999999	0.0516204259485315	9.8117975567937687	0.0329064453301596	-0.2444284375671625	-0.1266090876311226	0.0652730475269410	
+1.6770000000000000	0.0614259824815672	9.8226585696241528	0.0121406656266191	0.0010955450841458	0.2088288666329249	0.1184767856433829	
+1.6779999999999999	0.0727978915392203	9.8296761262425054	0.0433190925960201	0.3874153067022965	-0.2310026241345502	0.0536679193487293	
+1.6790000000000000	0.0547767878755946	9.8187785040343538	0.0302948035828760	0.0086664767845805	-0.0590673289416884	0.2265568824380743	
+1.6799999999999999	0.0556582659274553	9.8325407429780913	0.0230025996634371	-0.4126738320121250	-0.0351087899318827	-0.2202156338631241	
+1.6810000000000000	0.0624051124145794	9.8121234918761235	0.0356246120300324	-0.0754440889134380	-0.0089953876305336	0.1043743593811919	
+1.6819999999999999	0.0691651538497378	9.8290014010289308	0.0200814536707713	0.2368482646114843	0.0302915360485971	-0.0678651398071853	
+1.6830000000000001	0.0762024759650051	9.8441468989986056	0.0394829689107831	-0.1375687973114854	-0.2042148943736343	0.3705765263762654	
+1.6839999999999999	0.0811783931725554	9.8373693519791310	0.0048520759815302	0.0553431272833045	-0.1180108634234039	0.2992639426759259	
+1.6850000000000001	0.0614688677324902	9.8395486028441770	0.0399265836304995	-0.0223091569291048	-0.0667935292876560	0.3319246987537886	
+1.6859999999999999	0.0720678018078072	9.8325273667556878	0.0288931769928154	-0.1921451007835376	0.2937122608807144	0.0313454163248928	
+1.6870000000000001	0.0622038857954898	9.8254075428676018	0.0281160118416815	0.1293142304100760	-0.0536587241734592	0.2120481629733451	
+1.6879999999999999	0.0638683861013545	9.8174511147154302	0.0446867188018086	-0.0374872988022739	-0.1002743191495396	-0.0523447685352232	
+1.6890000000000001	0.0654523585300599	9.8045234281004952	0.0270518005891663	0.1621375784073057	0.0136435546255771	-0.0498770727031753	
+1.6899999999999999	0.0638902051055055	9.8040796493171474	0.0301757173612667	0.1547005060248949	-0.0636022598483852	0.2715382068029481	
+1.6910000000000001	0.0555058419687989	9.8229591081883925	0.0362859642032108	0.1170454187372823	0.0939248760649187	-0.1599685177757401	
+1.6919999999999999	0.0677855788047523	9.8290973303078122	0.0277124583647127	-0.1914475015480753	-0.2798627390030390	0.1973324510225895	
+1.6930000000000001	0.0674329833486969	9.8311620754137952	0.0262642368005211	0.0195255159285793	0.1048332571651805	0.1284826439022809	
+1.6940000000000000	0.0670097844615989	9.8208220598170666	0.0302183238936285	0.3593899406161638	-0.0450859143181218	-0.0581253109389633	
+1.6950000000000001	0.0642601839791154	9.8236746443740799	0.0469094492939294	0.2058009967295465	-0.1415756990771223	0.1851101649155444	
+1.6960000000000000	0.0559054864602388	9.8000513046890347	0.0276059097118274	-0.0700699617411663	-0.2893670771929213	-0.0459266604570589	
+1.6970000000000001	0.0707404799522709	9.8163954822123447	0.0429807408873480	0.2313115454280886	0.0009341808956738	0.3096395174595101	
+1.6980000000000000	0.0757529926517534	9.8194323739044318	0.0323592964611196	0.0470246675266145	-0.1362530750975957	0.2123442635861511	
+1.6990000000000001	0.0639352638188456	9.8423814751627017	0.0375976876552225	0.3093703176541113	-0.0081930867948602	0.0507367768789119	
+1.7000000000000000	0.0613987296577798	9.8068286909673574	0.0402635177944965	0.2007596256160489	-0.0955277781843985	0.3149922877155931	
+1.7010000000000001	0.0686010595588449	9.8417251828611789	0.0466698846126675	-0.1299555924467724	-0.2006098103150994	0.0953504642915521	
+1.7020000000000000	0.0564416620980774	9.8399620563115739	0.0523814685866436	0.2831396989256950	0.0311327671082318	-0.0898245843937835	
+1.7030000000000001	0.0693586520626787	9.8154842445928736	0.0368339440823550	0.1404487196391287	-0.1856384322951294	-0.0028820032415315	
+1.7040000000000000	0.0525469736154465	9.8404923376743589	0.0227834226504522	0.0590706288523840	0.0171268098103438	-0.2018706489034687	
+1.7050000000000001	0.0807240558623799	9.8110673804768105	0.0451787895837353	0.3052516758055873	0.1439968586745916	-0.0527444151060298	
+1.7060000000000000	0.0522927248992435	9.8246764472659827	0.0224465799799646	0.0151279155586029	-0.0156992459940610	-0.3114271788276266	
+1.7070000000000001	0.0947733716720108	9.8242874390255448	0.0482652838550963	-0.0138021133671712	0.0749987771009125	0.2096920312622664	
+1.7080000000000000	0.0654367254394909	9.8055774000711811	0.0408728390554742	0.1531317512856135	-0.3801753965189977	0.0751042492220418	
+1.7090000000000001	0.0649513747182743	9.8219628087665054	0.0108986292244354	0.0878316016284584	-0.1200314085209547	0.1002164432804789	
+1.7100000000000000	0.0652712593485566	9.8457437892732447	0.0323518358201844	0.3734569289451674	-0.2671056793313266	0.1716332707391469	
+1.7110000000000001	0.0524460701290510	9.8343675340281393	0.0302647465689211	-0.0073760622439196	-0.1755009378296127	-0.0589624835489247	
+1.7120000000000000	0.0496432962926462	9.8096265803538447	0.0253843248183144	-0.1982215251250787	-0.1549929746954618	0.1951851942047008	
+1.7130000000000001	0.0665292002914472	9.8202094165416671	0.0618289462379020	0.2895157270757807	0.3438023861903255	0.1829679473486450	
+1.7140000000000000	0.0692497029109295	9.8250963145376069	0.0545428109483058	-0.2934685813079083	-0.1034300775669538	0.0186328385382529	
+1.7150000000000001	0.0778107519727938	9.8050440478225376	0.0288959792809536	0.1013237690626341	-0.1362852132401069	0.1838212144201331	
+1.7160000000000000	0.0706025863201985	9.8458035035051328	0.0273030085689195	0.2261219154455965	-0.2992412127245605	0.0421861484673021	
+1.7170000000000001	0.0756440541481021	9.8113000348479922	0.0405910042738207	0.0495877956177014	-0.2577151739533258	0.0062282815022971	
+1.7180000000000000	0.0735974216383426	9.8245932342972093	0.0124201982508931	0.2550848302190665	0.2978535954691429	0.1448297833463878	
+1.7190000000000001	0.0599191118448413	9.8303522524741727	0.0221445960285567	0.2059356912671059	0.1146429054596139	0.0030645729552616	
+1.7200000000000000	0.0440311134312258	9.8266141512212712	0.0442775447945030	-0.0694241003860951	0.0685280519030533	0.1571797833310929	
+1.7210000000000001	0.0501845227279953	9.8161881340327106	0.0288590187628385	-0.0336602971066086	0.0121084909142932	0.0410088098735763	
+1.7220000000000000	0.0595301079445790	9.8260556229996379	0.0627530542721937	0.0038452966361639	0.1273578346346729	0.3144304441441975	
+1.7230000000000001	0.0612548208843711	9.8335374084782377	0.0310785175861421	-0.0495353256740850	-0.0434895918872748	-0.0486407625817032	
+1.7240000000000000	0.0806126259003170	9.8025348854199361	0.0317455939582930	0.0267938206275206	-0.1558299401431256	-0.1123946570918730	
+1.7250000000000001	0.0704957900293919	9.8082084816293733	0.0272567770610991	0.0931882972153514	0.0216103422840985	-0.0528304175291162	
+1.7260000000000000	0.0562519279662518	9.8241267168234767	0.0381956765499050	0.0105530712871230	-0.1069736726194220	-0.0935011904114714	
+1.7270000000000001	0.0518740261453548	9.8463596615230333	0.0403336229245303	0.3404853045062891	-0.2652970831058363	0.1846138434901589	
+1.7280000000000000	0.0516833689160534	9.8230184362826467	0.0462919090058527	-0.0321666460221690	-0.1305859612274483	0.1778334049816340	
+1.7290000000000001	0.0590257879048145	9.8526327270527059	0.0403813024259332	-0.1472369744936023	-0.1507489279247172	-0.0315112758498451	
+1.7300000000000000	0.0720867045857260	9.8421281798708762	0.0543107156264071	0.1131741128446944	0.1700605073971407	-0.1047431594794580	
+1.7310000000000001	0.0760932311336688	9.8021786805591375	0.0331683173788347	0.1485725472395383	0.3748521124553751	0.1646428367259061	
+1.7320000000000000	0.0822012500400171	9.8182609098332563	0.0351828183594369	-0.0189450216121175	-0.2380412289403291	0.0087329151335621	
+1.7330000000000001	0.0607415181742892	9.8412434421161823	0.0477964712948798	0.1867873510533720	-0.0396481386448025	-0.3796561343523984	
+1.7340000000000000	0.0492088880718513	9.8379662841587603	0.0431582044523265	0.1318236435093254	-0.2113253167961044	0.2658655683541813	
+1.7350000000000001	0.0511465866642997	9.8228308738315633	0.0231209460013412	0.0673807144018022	-0.0718762669067920	0.1470260150990582	
+1.7360000000000000	0.0647763543687681	9.8382753211861207	0.0305554312660567	0.3768105336418933	0.0418115354889357	-0.0819062713667434	
+1.7370000000000001	0.0822384190703335	9.8455038219033550	0.0295128119908743	0.0552577357277570	-0.1382987359292346	-0.0036246596296252	
+1.7380000000000000	0.0793790631823394	9.8313811490365470	0.0461800692865080	0.1571159912465114	-0.0310821025867502	0.0260693434998941	
+1.7390000000000001	0.0814109691385368	9.7896317637873960	0.0421117753701169	0.0948600615552700	-0.1668622252518017	-0.0011976997766654	
+1.7400000000000000	0.0509064240669635	9.8162143780352729	0.0374140593747406	0.2133270541903405	-0.0817729424136855	0.2081401250231776	
+1.7410000000000001	0.0459814201512083	9.8170046542923295	0.0359940780345174	0.0595815719681953	0.0069004055516021	0.1514574497578745	
+1.7420000000000000	0.0779840345022655	9.8230298620476475	0.0419828904484504	0.0500982241705952	-0.2625762374677783	0.2382444256097911	
+1.7430000000000001	0.0577879559613398	9.8505878890970333	0.0416513385029560	-0.0880241709807233	0.0251080412091070	0.1232322216395027	
+1.7440000000000000	0.0391485826079993	9.8270153554672071	0.0473841076681794	0.1502267129312231	0.0831977930026972	-0.0940304760260095	
+1.7450000000000001	0.0695330834360822	9.8483752002761591	0.0280122841124997	-0.0429943356568615	0.1270721912582302	0.1140427866274274	
+1.7460000000000000	0.0944522553120837	9.8275893469968008	0.0435047800927734	0.2421606962152997	-0.0936010550869840	0.1020182091309555	
+1.7470000000000001	0.0669928368344736	9.8325815801025005	0.0195347376244081	-0.1076259479628093	-0.1133066628223332	0.5076687996264176	
+1.7480000000000000	0.0403193034637661	9.8326656337697926	0.0413376813338908	-0.1031547501621925	-0.1346834596661285	0.1617413990905801	
+1.7490000000000001	0.0401002615960771	9.8295685878556931	0.0362415088885209	0.0216401617743661	-0.2001921399127294	0.0285850426209293	
+1.7500000000000000	0.0754750314744390	9.8342893632145589	0.0354114069062151	0.1039894061412027	0.0217063865183844	0.2405182257205639	
+1.7510000000000001	0.0549657071545595	9.8263530448666199	0.0482368010443856	0.0550644268338623	0.1540045191431904	-0.1890342317556667	
+1.7520000000000000	0.0606585253415488	9.8141001527317577	0.0556676337253120	0.0000972814153246	0.1379310945926026	-0.0276749778203737	
+1.7530000000000001	0.0358303491987783	9.8316303014704722	0.0158476229139021	0.2605932212325095	-0.0612400601093504	0.3205092555437870	
+1.7540000000000000	0.0448234413603420	9.8305901887092357	0.0331355110948638	0.0327752040342154	-0.0447071392145634	0.1357416581053673	
+1.7550000000000001	0.0658041145721988	9.8068227023102086	0.0074291115093672	0.0471153611218642	0.0455621980509785	-0.1563415187233420	
+1.7560000000000000	0.0779588377966780	9.8445269054445124	0.0185958947936959	0.3186640187128543	0.0253626189402255	0.2004293406793611	
+1.7570000000000001	0.0702426055499580	9.8364106288869237	0.0285992541341344	0.0227753705030854	-0.1278074089159602	0.1377240294475645	
+1.7580000000000000	0.0837651885826905	9.8188359202620585	0.0306356250530967	0.0732742127606294	0.0047272181176856	-0.0120000168511049	
+1.7590000000000001	0.0739959458540968	9.8184591702604607	0.0380647416181977	0.1836912123246012	0.2244679770787559	-0.1803618555994075	
+1.7600000000000000	0.0748717303800741	9.8308560343879385	0.0202489309736374	0.0925504409231922	0.2382116080758770	0.0597340009626088	
+1.7610000000000001	0.0755483396067628	9.8329612900378951	0.0465761194108085	0.0761081162268494	-0.2104056474483745	-0.1020431167858463	
+1.7620000000000000	0.0510569306978521	9.8194876612491839	0.0393337201360784	0.0862470197517677	0.1258700817786231	0.0403764497155608	
+1.7630000000000001	0.0821118749600971	9.8313418725961341	0.0584196532867234	0.0531274372727880	-0.0773432521671785	0.2739941189853227	
+1.7640000000000000	0.0354353815059106	9.8151537821088759	0.0287889458067093	-0.0613277920290870	0.0604039024381139	0.2016468503136178	
+1.7650000000000001	0.0696714200194141	9.8320245208272858	0.0364217995749340	-0.0443753360391024	0.0477636122651951	-0.1521881035729377	
+1.7660000000000000	0.0565570963343711	9.8509622340503036	0.0356812168097834	0.1615712422013333	-0.0750171144543523	-0.1595954015237240	
+1.7670000000000001	0.0756298347242245	9.8373117761072653	0.0315265602217264	0.5448743043081450	-0.1410566085962752	-0.1308708743994212	
+1.7680000000000000	0.0952983151497644	9.8307499315645988	0.0271413482242805	-0.1491660897077424	-0.1227732935924244	0.0271656828228456	
+1.7690000000000001	0.0287877283942710	9.8389882201858594	0.0453115918010272	0.1082614357362386	-0.1117983774006691	0.1239407906835235	
+1.7700000000000000	0.0668817892437599	9.8255244029801077	0.0318792901943276	0.0566825642491502	-0.1388209474642991	0.0711642315685579	
+1.7710000000000001	0.0669979399679831	9.8245775665982169	0.0415127991459662	0.1405702482024898	-0.3098195605592352	0.0697455190575145	
+1.7720000000000000	0.0596214017056655	9.8318917749301864	0.0461646985134464	-0.2619916522759465	-0.0049344491518249	0.1438416050417409	
+1.7730000000000001	0.0650050107422975	9.8626262746122784	0.0286572330144634	-0.0004803659464263	-0.1979729618795889	0.0553118302245431	
+1.7740000000000000	0.0645845123582381	9.8078659256299954	0.0147879543726775	0.2334139345216512	-0.0748755843645563	0.1450007113744237	
+1.7750000000000001	0.0627726600820084	9.8378594086616999	0.0606197263535155	0.1820843680769989	-0.2465281384811872	0.2186329205817815	
+1.7760000000000000	0.0770502777638497	9.8173357673621080	0.0357604212853487	0.0060783447939610	0.0541027986082705	-0.0362314392640092	
+1.7770000000000001	0.0629206829166708	9.8263213346380152	0.0487832187748596	0.0847988953638731	-0.1852078461024792	-0.2284380037510703	
+1.7780000000000000	0.0728057326163135	9.8265313794029492	0.0382871741817978	0.1111169643548080	-0.0599846178290719	-0.1261938871912475	
+1.7790000000000001	0.0755019793931965	9.8274361093302804	0.0283232998681289	0.0655107495598629	-0.0465215471822725	0.0055513147820979	
+1.7800000000000000	0.0627897695053682	9.8201183601867044	0.0348261659585519	0.0910581102683103	0.1018253653345484	0.1979592770375852	
+1.7810000000000001	0.0652573118660271	9.8514871222854197	0.0314560213170771	0.0532942012403252	0.0502974331754918	-0.2218918803548861	
+1.7820000000000000	0.0720422260843692	9.8570560851954259	0.0237350891115170	-0.2630944182545985	0.1111867960384084	0.3490277398285827	
+1.7830000000000001	0.0576446824074006	9.8229316733858969	0.0392608173171416	-0.1289042267786772	-0.0694701962361856	0.1023207073162366	
+1.7840000000000000	0.0664258909358702	9.8251739618623972	0.0356323855277541	-0.0156982253584896	-0.0050281865664587	0.0686213015918968	
+1.7850000000000001	0.0863334063274402	9.8169839942596138	0.0436135573256597	0.0056630438789320	0.0933094106305402	-0.0118255189408529	
+1.7860000000000000	0.0490027869024723	9.8409787600367782	0.0416002479726918	0.0329485202021235	-0.0489105790722902	-0.0747508917688076	
+1.7870000000000001	0.0738815399746119	9.8245036016774616	0.0450526710467767	-0.0735173721218044	-0.2172840027775053	0.2032096070096114	
+1.7880000000000000	0.0467598074762695	9.8477781032804010	0.0321499011771801	-0.2133858417405281	-0.0223437998996638	0.1647223567210556	
+1.7890000000000001	0.0586089086527880	9.8366076648978336	0.0521284384756986	0.3325775817786964	0.0632976200728790	0.2572736430377175	
+1.7900000000000000	0.0577754924763445	9.8134624825242529	0.0406110214315451	0.2183909179960947	0.1876799205397395	0.0480653052295227	
+1.7910000000000001	0.0836927096743943	9.8046623563342905	0.0177627773122069	0.1645455055033095	-0.1634399721913983	-0.0448033118576191	
+1.7920000000000000	0.0586825855561492	9.8207016872657409	0.0479179375968085	0.0536724977839801	-0.2252125050317118	-0.1748293749018078	
+1.7929999999999999	0.0714862683523028	9.8244597162361575	0.0220684430759244	-0.0209285556689945	-0.0709523287987630	-0.1603634244816328	
+1.7940000000000000	0.0483583769791558	9.8198638872396469	0.0382846405364956	0.3204144832254179	-0.1768736411272908	0.1068410077236801	
+1.7949999999999999	0.0489212154709572	9.8219633520410117	0.0384631696207266	0.2331145883740411	-0.0768862347050472	0.0547377184649259	
+1.7960000000000000	0.0625088578170045	9.8080787661627742	0.0450101516799007	0.0779605656883445	0.0484271515425345	0.0095609145557756	
+1.7969999999999999	0.0616359691694780	9.8414031425138759	0.0418427422537975	0.0208662151380591	0.0256671978682212	0.0596792720186171	
+1.7980000000000000	0.0560422847897683	9.8151532466248312	0.0591871656235277	0.1412410120413076	-0.0201553954272131	0.3847298890480210	
+1.7989999999999999	0.0493060520511172	9.8187147565502304	0.0208301242375177	0.0830601652403838	0.3544862396026358	0.0139991963437838	
+1.8000000000000000	0.0609204571695044	9.8339703122332391	0.0490814727838168	0.4063829301553582	-0.2955177311265469	-0.2330952030724255	
+1.8009999999999999	0.0685726218052242	9.8228264821230304	0.0269269383922546	-0.1648294782145950	-0.0534248150969672	0.1951899529432369	
+1.8020000000000000	0.0795409711540165	9.8258695497115376	0.0425123337200926	0.3115350019907543	0.0582303442877583	0.5572502667807214	
+1.8029999999999999	0.0595999972694223	9.8307617875878499	0.0362760521928962	0.2560439770807552	0.0575580268675423	0.3596673337043217	
+1.8040000000000000	0.0828017520237473	9.8249613734021608	0.0528789183090982	-0.0626991448044631	-0.1322915612365795	-0.1405978494647293	
+1.8049999999999999	0.0894770902401863	9.8375478112716497	0.0364792521106129	-0.0865497898142091	-0.2580474136513930	0.1346066539716986	
+1.8060000000000000	0.0636640144426527	9.8246650670722406	0.0162007532386622	-0.1284620721969731	0.0684406937068459	-0.0421091140883711	
+1.8069999999999999	0.0596023774490905	9.8260983087952969	0.0223288571547779	-0.1982801053644537	0.2345151394644366	-0.0394817602812286	
+1.8080000000000001	0.0678003472146468	9.8144010108409638	0.0469864658540325	0.0339878219075043	-0.2649538691080314	0.1980200373862514	
+1.8089999999999999	0.0733347482206876	9.8014572157295241	0.0567647132249699	0.0786739515015156	-0.1714194623580088	0.0855598936628921	
+1.8100000000000001	0.0677713548115975	9.8152290547523595	0.0254562823640357	-0.1160925880578400	-0.0396825515263926	0.0522079853660878	
+1.8109999999999999	0.0556372853571462	9.8187395672010762	0.0431611583986829	0.1833968344035555	0.0784889539427831	0.2398341276965953	
+1.8120000000000001	0.0600791126950273	9.8378720907918602	0.0314847867100102	0.2014525108419013	0.0694685503150649	-0.0957508110105120	
+1.8129999999999999	0.0633664451700521	9.8357412202219106	0.0490351701702151	0.0586266150697677	-0.1422479491393714	0.0234764712665865	
+1.8140000000000001	0.0897093326127830	9.8194294818195171	0.0535062691723655	-0.2149136213770057	0.0209482426829324	0.1528080132369732	
+1.8149999999999999	0.0601510168873315	9.8395096826155424	0.0279630409910476	-0.0187156954138410	0.0280817553031239	0.3044507476640076	
+1.8160000000000001	0.0757626086969259	9.8285924963105700	0.0362158697390964	0.4651487091122433	-0.0147214311545928	0.2150023884500307	
+1.8169999999999999	0.0834450029539256	9.8126688507569479	0.0430540274203227	0.1966190588562154	0.1210137109653107	0.1485637468524146	
+1.8180000000000001	0.0724266207618609	9.8126447143854563	0.0322885323346159	0.1368515099126751	-0.1249751472099968	0.0887319156744476	
+1.8190000000000000	0.0611114243678538	9.8101630425852075	0.0331273079142594	0.2365061290778823	-0.3964444841010245	0.2479766108198385	
+1.8200000000000001	0.0923042926760413	9.8306451433007300	0.0397478740794645	-0.1175304255476919	-0.2372402694857772	-0.0529864612231737	
+1.8210000000000000	0.0575616661185663	9.8304132463239231	0.0400268357051052	0.1752508926747704	-0.0883567918195608	0.0574557713956829	
+1.8220000000000001	0.0587457552117730	9.8364077781047161	0.0370048026239789	0.1216617315993184	-0.1828220995683218	0.3056686242233855	
+1.8230000000000000	0.0496937041362933	9.8290392194014338	0.0227191601348973	0.5731745698592323	-0.2571455231528555	0.1442379363622226	
+1.8240000000000001	0.0385872219162717	9.8299815247906199	0.0486452067035570	-0.2071418062826481	-0.0876022564087289	-0.1796758278279336	
+1.8250000000000000	0.0945674169948761	9.8326330225541838	0.0206643445616612	-0.1416046901833384	-0.0762938908337873	0.1809545481256910	
+1.8260000000000001	0.0651568775053292	9.8345784125628555	0.0365031208051651	-0.0823295382695300	-0.1070795079002196	0.1298198728925209	
+1.8270000000000000	0.0813391372434298	9.8357320699625763	0.0296408514567815	0.2194554346236139	-0.1523404114501362	-0.1648360875794007	
+1.8280000000000001	0.0512183728882222	9.8345384391499415	0.0428549448904504	0.0624897736441611	-0.1100720659450879	0.1376586247808134	
+1.8290000000000000	0.0746570103440968	9.8364263245847319	0.0610619119232156	0.1554875920441804	-0.0199757507585592	0.0594265407900828	
+1.8300000000000001	0.0437419370503163	9.8451080822161128	0.0326468123123990	0.0248594259039394	0.2205246934168197	0.1324978379537398	
+1.8310000000000000	0.0605514111976576	9.8341017700701823	0.0471797231224291	0.1638744559080306	-0.1389775685562821	0.3864314533558610	
+1.8320000000000001	0.0710512461768741	9.8242798315013360	0.0314328395845155	0.1183803202819428	-0.2119805101178549	0.1539719336078250	
+1.8330000000000000	0.0624826946227122	9.8261855464035825	0.0267387358023146	-0.1552469013788824	-0.0097554456983900	0.2163262071944556	
+1.8340000000000001	0.0702364193437978	9.8051413054256233	0.0456334756648254	0.2102290620553842	0.0971411665058957	0.1855336140856295	
+1.8350000000000000	0.0755033967907378	9.8210992551082477	0.0330047031607994	0.0491915493248188	-0.0793369617004323	0.1797066719408962	
+1.8360000000000001	0.0564395063368775	9.8565216460836407	0.0522179668142564	-0.2446361049156088	0.0285793774455546	0.0117153692562541	
+1.8370000000000000	0.0570959865235179	9.8315098862637758	0.0298094782014000	0.2218226770898208	-0.1051901105719136	0.1556280543655892	
+1.8380000000000001	0.0427094857133773	9.8314411511161222	0.0440766015497737	0.1971027246626180	0.3064745123503215	0.0494617119878018	
+1.8390000000000000	0.0579864969051323	9.8213901327174575	0.0408869020566502	0.1814172333707268	0.0300989537350498	-0.1503839205138179	
+1.8400000000000001	0.0457375097189865	9.8494761419447343	0.0420503060344470	0.1102243078567852	-0.3334156347750057	0.1922962831018385	
+1.8410000000000000	0.0624221541800705	9.8111646838541979	0.0174072263147003	0.0850488459457194	-0.2642889277197957	0.2678714769225341	
+1.8420000000000001	0.0560929370622863	9.8239628541428079	0.0248647597783272	-0.1126514216199438	-0.1897595890497287	0.0431448885417891	
+1.8430000000000000	0.0510837596896075	9.8437006383631225	0.0357587221849937	-0.0876699009398556	-0.0196683017922195	0.0921544826548631	
+1.8440000000000001	0.0857347423324804	9.8309130897082433	0.0400947341827422	-0.1414227795089185	0.0350185900860361	0.1352578730253690	
+1.8450000000000000	0.0602561052409587	9.8038341101586948	0.0262699478579811	0.1077831342736550	-0.0416259484900845	0.2994105477937828	
+1.8460000000000001	0.0642061851340035	9.8132937340436737	0.0292021996878567	-0.0682722661703230	-0.3068133502466425	-0.1389780494187848	
+1.8470000000000000	0.0739097329578848	9.8387086639337671	0.0482629806070917	0.1912910906339509	-0.0270603171403261	-0.1128253701782409	
+1.8480000000000001	0.0520099293047694	9.8230923755376143	0.0465239713419896	0.1388555685785606	0.0954158860881897	-0.0267517313519400	
+1.8490000000000000	0.0738284418075248	9.8262758972711062	0.0485903084118313	-0.4293091250882772	-0.2957484323966411	-0.0290666565687783	
+1.8500000000000001	0.0629052292900185	9.8301977764790571	0.0400706028213179	0.1706882717027981	0.1254355882435801	0.1337093724805901	
+1.8510000000000000	0.0622386694978924	9.8238040888099185	0.0432573163197033	0.0689034134298295	-0.0744119215496285	0.2693388650627794	
+1.8520000000000001	0.0731254158741077	9.8455319307366285	0.0111029240546776	0.3108434114626170	-0.1355062442528628	-0.0488128056052655	
+1.8530000000000000	0.0768059547867420	9.8374130025718074	0.0181599905762872	-0.0271310960230369	-0.5728003563998623	-0.0074724299187106	
+1.8540000000000001	0.0692503517936015	9.8291780594146250	0.0254644603193193	-0.0189672467486802	-0.0744966342239576	0.1478562776295989	
+1.8550000000000000	0.0714819646086320	9.8200452099485283	0.0477221462583766	-0.1267859462289311	-0.0135852057568789	0.2387463315637184	
+1.8560000000000001	0.0517156287810302	9.8139644595670319	0.0308769201045790	0.2058323343156186	-0.2506823797933492	0.3770873373868822	
+1.8570000000000000	0.0616199958017276	9.8381805872948522	0.0301040177334406	0.0171682217994516	-0.1984510932244426	0.2891161925402612	
+1.8580000000000001	0.0760185224784012	9.8215463001019518	0.0295695893816153	-0.1911618187565819	0.2286190320978486	0.2110032130180597	
+1.8590000000000000	0.0592616144922889	9.8015906805786059	0.0251067467228524	0.2049527711549128	0.1717849614102588	0.1623218032266140	
+1.8600000000000001	0.0479807298382474	9.8513023839344296	0.0463747715279018	0.3831441549262116	0.0334403895126532	0.2691156526271839	
+1.8610000000000000	0.0645915224067694	9.8342524303415075	0.0379700290796543	0.0789786913857489	-0.2001164276976343	0.0519903447344406	
+1.8620000000000001	0.0607498178010180	9.8217410854823761	0.0412959326488183	0.2919618087315281	-0.1064408676862503	0.0953561285702898	
+1.8630000000000000	0.0763088904049213	9.8141388597515284	0.0441010405845528	0.1043286050037945	-0.1261969871783348	0.0706964056273172	
+1.8640000000000001	0.0611437545813414	9.8418870479115803	0.0341386833104305	-0.0058544520586386	-0.0069967645121965	0.1969846277462592	
+1.8650000000000000	0.0689177333210011	9.8089035523094452	0.0408687961649635	-0.0165247642972226	0.2404127341530800	0.0054081597849583	
+1.8660000000000001	0.0730444731098732	9.8301172988915759	0.0395565615816356	0.1229029002827004	-0.2686919426080788	0.1223062554421883	
+1.8670000000000000	0.0849315906341463	9.8180177265804183	0.0393485786387552	-0.3301080023558483	-0.1998880179259268	0.2084696568780488	
+1.8680000000000001	0.0561136203719623	9.8243172052786516	0.0210079604248561	0.1403019189079160	-0.2211055878307818	-0.0001584874126254	
+1.8690000000000000	0.0906673790197499	9.8158112177226542	0.0354624412696427	-0.0729934496097205	0.1904624517706315	0.2850199861848647	
+1.8700000000000001	0.0813095917329583	9.8458180133250774	0.0377082494285374	0.0575892692550134	0.1012917854104317	0.1668013080464198	
+1.8710000000000000	0.0646965055500272	9.8152273912984906	0.0507078231071096	0.2552866797643285	-0.0272144474122810	0.1360693963121088	
+1.8720000000000001	0.0669182576881059	9.8262720816692308	0.0384609007484124	-0.0217236899537887	-0.0064146996616812	0.2967681661231005	
+1.8730000000000000	0.0702842843748365	9.8312600458745170	0.0268377607252477	-0.0717444742417865	-0.0969415611195956	0.1258761510321368	
+1.8740000000000001	0.0647983405168037	9.8261673025198455	0.0414580457956730	0.0167025521874362	-0.3139188993232598	0.2486106045418771	
+1.8750000000000000	0.0576594004363259	9.8251889874197857	0.0272610294527576	-0.1216492946679413	-0.0363691577177005	0.0681191046913225	
+1.8760000000000001	0.0526580879225475	9.8491145406306497	0.0443611436890707	-0.0081311543232415	-0.1135999687831678	0.2179082177311381	
+1.8770000000000000	0.0639153998050598	9.8592481745130254	0.0335074177190529	-0.1568041225881225	0.0391402500513268	-0.0018548291666056	
+1.8780000000000001	0.0558249776408260	9.8099235334678703	0.0561507304727479	0.1829921212913136	-0.1878870426396477	-0.0829210861437919	
+1.8790000000000000	0.0752108829021719	9.8265539285442500	0.0449232696129399	-0.2258610816511198	-0.0465070794604713	0.2707782797837764	
+1.8800000000000001	0.0290252473995950	9.8247060103763868	0.0286158488378989	0.2103787925803600	-0.0207027085419725	0.2423415758407965	
+1.8810000000000000	0.0756746237772022	9.8250703841754916	0.0202254663892424	0.0393231968931990	0.1154248238140769	0.0096034114028114	
+1.8820000000000001	0.0747345387693154	9.8336760808157102	0.0489866816588451	0.1047735235870983	0.0463606319224095	0.0053700993185926	
+1.8830000000000000	0.0545812103701409	9.8338451981162933	0.0464651934395338	0.2700831130977662	0.0887889491084424	-0.1718346733181935	
+1.8840000000000001	0.0640698029924102	9.8283090733484837	0.0467918432295652	-0.1645400179992300	0.0395660709202478	-0.0132359005642383	
+1.8850000000000000	0.0678069656269930	9.8272004984347010	0.0261603066087799	-0.1725934827111150	0.0165458864540713	-0.0809057010859720	
+1.8860000000000001	0.0743960738461753	9.8470185420035090	0.0450200419223390	0.0580331010242797	-0.2291017473170964	0.1740257184950386	
+1.8870000000000000	0.0741226568084548	9.8098040235257162	0.0344945576357914	0.0255622957825084	0.2025588307929140	0.1956332437718555	
+1.8880000000000001	0.0612478727355959	9.8320412978829808	0.0215427227808141	0.0499625396202012	0.1210432982265167	-0.1933368199999318	
+1.8890000000000000	0.0543309848157983	9.8423718056776650	0.0170374332762620	-0.0031008196026548	-0.1594760967509361	-0.0092633892056593	
+1.8900000000000001	0.0530845010296130	9.8167121651203182	0.0282224011360671	0.2582958107334681	-0.1266835019460582	0.0825283749091324	
+1.8910000000000000	0.0559570091510222	9.8197624372421188	0.0360420465956232	0.0780540398170618	0.0910637937017356	0.2325206566524045	
+1.8920000000000001	0.0633308077254921	9.8163603932561951	0.0355522053152309	-0.0200781760022338	0.1403234898434437	0.0743037919974396	
+1.8930000000000000	0.0837187946230911	9.8146869077040932	0.0355852875756002	0.2406030094432774	-0.1004643483221539	0.1468586842999598	
+1.8940000000000001	0.0731249313563021	9.8266641206815954	0.0132176361528722	-0.0141125839759182	-0.1199099703641312	-0.0412631355433323	
+1.8950000000000000	0.0603723078910810	9.8294534082925633	0.0372977411856934	0.1152294581646727	0.2876653205109365	0.0270038473952262	
+1.8960000000000001	0.0623637577746938	9.8392348912263383	0.0482934306652927	0.2101752927188886	-0.4010393529177964	0.2721926143819844	
+1.8970000000000000	0.0614587644423316	9.8481810623782220	0.0475457591085003	0.0454043785854688	-0.3826310994628724	0.0035764293499528	
+1.8980000000000001	0.0546421237464264	9.8293930453362695	0.0355286121276609	0.1155835533246556	0.0577331040672183	0.1674898263453174	
+1.8990000000000000	0.0629193054367905	9.8299174347139537	0.0517692203513179	0.0855453950863642	0.1741348691527740	-0.0756448573877578	
+1.9000000000000001	0.0596315913745621	9.8339854876871033	0.0271051552113473	0.0531310465100159	-0.1045767902692036	0.2723352448506020	
+1.9010000000000000	0.0539400510893308	9.8338095567794905	0.0387309154116763	0.2330136703104259	-0.1390499898580105	0.1155752897894063	
+1.9020000000000001	0.0547262830027573	9.8162661026037199	0.0258295458498181	0.1514263094385384	-0.2339515446709096	0.1634006178970322	
+1.9030000000000000	0.0811957752379055	9.8290858095276086	0.0216083100935224	-0.2375984358671429	-0.0472903922267342	0.0395168013859166	
+1.9040000000000001	0.0678917544768055	9.8194322811923254	0.0260621288887136	0.0893967175594478	0.0063913229908692	-0.0093251207410301	
+1.9050000000000000	0.0587922493764781	9.7862218782539152	0.0413505542754953	0.1427437616355169	0.2085671935890749	-0.0226335527083762	
+1.9060000000000001	0.0568553238173711	9.8438433061941986	0.0300238929759914	0.0048494460202549	0.0025888337841772	0.0932298099980571	
+1.9070000000000000	0.0732387457585376	9.8204758436017539	0.0213943650782338	0.2892189560655241	-0.1705617023171845	0.2301580773076272	
+1.9080000000000001	0.0833240026378879	9.8106519199287554	0.0430653669661568	0.1714688418684837	-0.1564302938173387	0.1023586184436504	
+1.9090000000000000	0.0416336370574462	9.8342443908175863	0.0213301932191691	0.1475021577928571	-0.1592185626228083	0.0602189173928953	
+1.9100000000000001	0.0411392645312865	9.8347722596458436	0.0311287840896580	-0.0106423195060903	0.1236106468425464	0.0122978326343637	
+1.9110000000000000	0.0523178503990252	9.8284782606506447	0.0279855249009101	-0.0231312385853829	-0.1978487464995510	0.1751967788070219	
+1.9120000000000001	0.0899656826499424	9.8332603948398241	0.0450317351551524	-0.0710685631965858	-0.1935112243119661	-0.3120108536678111	
+1.9130000000000000	0.0608290995804199	9.8197565792187316	0.0432623303768309	0.2539257587785912	-0.0683443643353665	0.0954480437580180	
+1.9140000000000001	0.0649383472124951	9.8324265649451323	0.0449257815205324	0.2569638210265268	0.0710313498998256	-0.2407443211114051	
+1.9150000000000000	0.0820811938553440	9.8313734091801734	0.0490407618684657	-0.0167091067608187	-0.0702811503989380	0.0124115848649218	
+1.9160000000000001	0.0709359105379826	9.7995841244069251	0.0380300892497109	0.1793759844460961	0.0627832629128342	-0.1652151729847806	
+1.9170000000000000	0.0558712405866554	9.8321039355357218	0.0340668097893685	-0.1156569143033959	0.0162719804029069	0.0104850366240391	
+1.9180000000000001	0.0807379854300115	9.8369848577859482	0.0365232480709425	0.2297983886120267	-0.2786401971806289	-0.1501495970171909	
+1.9190000000000000	0.0505037571733904	9.8305637775550210	0.0590509436771232	0.1740614665084645	-0.2021976646419360	0.1724321362919579	
+1.9199999999999999	0.0624595290846400	9.8319036433597233	0.0432665756119578	0.1327427494473044	-0.2420218594536994	0.0694150170139172	
+1.9210000000000000	0.0584553482102083	9.8133147009327715	0.0405156574336076	-0.1485314256643136	0.1120446623088859	0.2533764585437950	
+1.9219999999999999	0.0400016743599500	9.8281140546371191	0.0508692110587349	-0.1688180332846214	0.1114963671148512	0.0966318562312214	
+1.9230000000000000	0.0752328706650957	9.8259002416142192	0.0204646418429054	0.1988560947308450	-0.0341426656251068	0.1878193996338211	
+1.9239999999999999	0.0353315984537657	9.8339752378522025	0.0519503849514537	-0.3182875228382490	-0.0495556640567399	0.2743961684337275	
+1.9250000000000000	0.0767632621070136	9.8047848693170270	0.0432520170770934	0.0405398985299728	0.1682857246349815	0.1479393068813084	
+1.9259999999999999	0.0672703992224845	9.8363337609766788	0.0292399820558595	0.1779105201072122	0.0085364914366214	0.1763026768177490	
+1.9270000000000000	0.0526415982719900	9.8200654932874425	0.0295763897972049	-0.0733082744526214	-0.0875667876062436	-0.0804724584781520	
+1.9279999999999999	0.0675357397427365	9.8288873178176708	0.0330978082284971	0.0044040260037767	-0.0656455608667503	0.0113709143407482	
+1.9290000000000000	0.0704861558525806	9.8273158090669313	0.0426587794330781	0.2488245655064035	-0.0391167661144918	-0.1782294478233218	
+1.9299999999999999	0.0717521997518440	9.8391634750306629	0.0312864294171870	0.2225791869416953	-0.3128250249983397	0.4434369393000958	
+1.9310000000000000	0.0687189255661975	9.8170721548130082	0.0276045371220680	0.0296624065872815	-0.3124907147346975	0.1455566259066879	
+1.9319999999999999	0.0671762868626949	9.8306334422568806	0.0130217172318908	0.2498663061971523	-0.2348245559841965	-0.0919701756939560	
+1.9330000000000001	0.0843578213914983	9.8340040701864986	0.0481439175482598	0.1469190413796122	0.1383599516433417	-0.0730802737249207	
+1.9339999999999999	0.0587366691550971	9.8305009969421775	0.0333525125747768	-0.0515110759273087	0.2164894327748450	0.1425211543003076	
+1.9350000000000001	0.0654860722328479	9.8201427676038779	0.0318096423198848	-0.0338675918161013	-0.0575956009006079	0.0867518607080869	
+1.9359999999999999	0.0586450230140374	9.8264477637044099	0.0393267982244278	0.1336079293841091	0.0880898789540198	0.0252826640635780	
+1.9370000000000001	0.0831183191244893	9.8262112459648616	0.0527546901137575	0.1852618640055230	0.2776815390715839	0.2199446783066435	
+1.9379999999999999	0.0539851337392003	9.8339579342438714	0.0541543161566305	0.3057102982102429	-0.1186094583143142	0.0626474088032938	
+1.9390000000000001	0.0681942259113752	9.8271525136132674	0.0542464345844127	-0.0930977443009894	-0.0369248212964486	-0.1064787952456764	
+1.9399999999999999	0.0830487720489353	9.8473323198482792	0.0350683829711534	0.1939884878793772	-0.0467301481006428	-0.0377588330699364	
+1.9410000000000001	0.0677026323642368	9.8258318774009723	0.0219297639650192	0.1698703590177172	0.1263840818810087	-0.0522547444898827	
+1.9419999999999999	0.0846352234962268	9.8394614911291356	0.0397841901767872	0.1303475952864837	-0.3015978879867865	0.0428265441292313	
+1.9430000000000001	0.0509098728176779	9.8165317061793651	0.0518372889885176	0.1007089810304755	0.1643932291043989	0.1838353856973181	
+1.9440000000000000	0.0510176835842862	9.8182499388606157	0.0472762863718505	0.0689919054002174	-0.0878866026756147	0.0781752384951851	
+1.9450000000000001	0.0676372417393327	9.8092412714592925	0.0443324885213703	-0.1430121827202077	-0.0957194720785658	-0.0221253348267540	
+1.9460000000000000	0.0761324848292849	9.8120193658172035	0.0543743529145738	0.3788802751644429	-0.1034131448405211	0.0302416120492997	
+1.9470000000000001	0.0642172535947993	9.8406315297508709	0.0369829872823510	-0.0351879426527740	-0.0643651730981869	0.0977005004129753	
+1.9480000000000000	0.0449565026835963	9.8584638305193675	0.0363138863959859	-0.1474949672959018	-0.0724700279108206	0.2944031965805623	
+1.9490000000000001	0.0720407780639341	9.8396960973838734	0.0466259392075686	-0.1391583011107888	-0.2626777976124818	0.1038296802346787	
+1.9500000000000000	0.0677482128643953	9.8359890772048679	0.0474741814346536	-0.1313274191942668	-0.2728345771100568	0.1421978690047641	
+1.9510000000000001	0.0729295260851609	9.8170660639273279	0.0351317540678336	0.0269871709047742	-0.1878842596345537	0.1936158226796406	
+1.9520000000000000	0.0639645042048701	9.8141600527936959	0.0218484310842023	0.0570849380271379	-0.0540542880368329	0.3783512319731731	
+1.9530000000000001	0.0538259475386385	9.8426747603971840	0.0302121816758070	0.3787528143348058	-0.0103184719018143	0.1003088263769021	
+1.9540000000000000	0.0700827400551193	9.8146826625261951	0.0164953622925836	0.0544643952905627	-0.1063062355004238	0.2671495506358380	
+1.9550000000000001	0.0612221915955764	9.8302729511222502	0.0369145822171826	-0.0276638081147495	0.0359859691088154	0.3775311256200624	
+1.9560000000000000	0.0784389105872007	9.8309282323161558	0.0170040456826965	-0.0231684370788082	-0.1484508301414516	0.2605731783782289	
+1.9570000000000001	0.0732608916429314	9.8322366058630699	0.0543576759587537	0.0112834021208438	-0.0838632494662150	0.2535454376772185	
+1.9580000000000000	0.0608880038520528	9.8276980407956831	0.0427981789247126	0.1686696818783511	-0.1049272464305826	-0.0115806471879813	
+1.9590000000000001	0.0641121850190961	9.8343619874038968	0.0647207444730968	0.0805871168493227	0.0072545942520036	0.0149686595634017	
+1.9600000000000000	0.0465890935811068	9.8400810840322617	0.0418594266587499	0.1383388555377625	0.1345107144507438	-0.0282340949233818	
+1.9610000000000001	0.0472885063022637	9.8340207986735866	0.0404135322874042	0.0588791060840662	-0.0130122695706022	0.2199079539567714	
+1.9620000000000000	0.0616790513690122	9.8235005769678896	0.0235548039548279	-0.0296973619391152	-0.1269535182229681	-0.0368174810054010	
+1.9630000000000001	0.0703325507902257	9.8345782076708232	0.0480439721608391	0.0161890280909203	-0.0851877317478252	0.0521718188681069	
+1.9640000000000000	0.0852575058242895	9.8451079618047963	0.0181270491805253	-0.0288635863538714	-0.3360553566451882	-0.0248501284403739	
+1.9650000000000001	0.0606116284371457	9.8174044705216019	0.0684015513986000	-0.1316030031991849	-0.1264984505501439	0.1028511846076079	
+1.9660000000000000	0.0739709286675297	9.8254400728736737	0.0466888305412204	-0.0307968364006401	-0.1551414844198702	0.0904992823225337	
+1.9670000000000001	0.0783728003713222	9.8219015272234156	0.0459898199226596	0.2333087257653246	-0.3275888242148638	-0.1315781479745333	
+1.9680000000000000	0.0647148619403718	9.8288679844582454	0.0395101735655023	-0.0615501207781609	0.2252138297411797	0.1950624125283691	
+1.9690000000000001	0.0471693775430438	9.8028767219773965	0.0293637240932270	0.0342128886941895	-0.2142219653885882	0.3730717022458992	
+1.9700000000000000	0.0494534795710730	9.8261468085139168	0.0395604722762759	-0.0764429312562179	0.1481919398169940	0.1947073829539463	
+1.9710000000000001	0.0594303151999259	9.8121620129158735	0.0303708178721621	-0.0960517149224229	-0.0395910270062700	0.1919095975023311	
+1.9720000000000000	0.0400398718212924	9.8460482681690920	0.0357715810771566	0.0735022588502419	-0.0665901824506871	0.2753154579142070	
+1.9730000000000001	0.0800378000786110	9.8288385130539471	0.0512437689173419	-0.0908714755806772	-0.1579543013072623	0.0257793605002147	
+1.9740000000000000	0.0592973579287474	9.8218777120763985	0.0353245981042658	0.1032046800038052	-0.1400590877685026	-0.1226043748280301	
+1.9750000000000001	0.0654800404056183	9.8086299424381984	0.0500788842371014	0.2291480788653352	-0.0130350423633753	-0.0523674842583909	
+1.9760000000000000	0.0801476169135058	9.8268044090496023	0.0251718547648179	0.2000322605054973	0.1764377692668530	0.0872363174514490	
+1.9770000000000001	0.0619663203647039	9.8175016670326851	0.0396102511039078	0.0496363951532985	-0.0738106855864214	-0.0632765331738723	
+1.9780000000000000	0.0684715257192129	9.8241532170645183	0.0498286780069525	-0.0060414899215248	-0.0612614292303126	-0.0252651428507370	
+1.9790000000000001	0.0568544212064143	9.8376586399848023	0.0237029666853190	0.0018288898927522	-0.3086890802884906	-0.1130522125934693	
+1.9800000000000000	0.0781749071678882	9.8336564485766242	0.0586307572205730	-0.2253747641512913	-0.3955952369960808	0.2134879503665254	
+1.9810000000000001	0.0495142463699521	9.8360577434948535	0.0509722997607090	-0.2255303309623483	0.0514108299028657	0.1613067056009918	
+1.9820000000000000	0.0555514274686705	9.8358998102201181	0.0182268121243260	0.0631686426412241	-0.0197997851243592	0.0530532081602712	
+1.9830000000000001	0.0669740155596243	9.8376301239332555	0.0142303742274040	0.2303875382768387	-0.2160565773896486	0.2186549232794488	
+1.9840000000000000	0.0812137643768603	9.8163513282811046	0.0345480726260622	0.2888656348389626	-0.2433658157476187	0.0653300529085236	
+1.9850000000000001	0.0680668803473632	9.8354180980721928	0.0481212431331931	0.2040299729808405	0.1329325080720961	0.2830879933657988	
+1.9860000000000000	0.0497778199197979	9.8359059754327411	0.0254511758090382	0.0351124918559397	0.0331699719724062	0.0962852200751399	
+1.9870000000000001	0.0595140999808057	9.8083449724828693	0.0363625789668772	0.0546275345398702	-0.0109780265223835	-0.0366391008225895	
+1.9880000000000000	0.0851494626701870	9.8348340502298033	0.0562786503159896	0.0534784649471589	-0.0187537365644249	0.1977509273217574	
+1.9890000000000001	0.0582268047920056	9.8434833694367558	0.0453940008762432	0.1075761856710802	0.2227167710463236	0.1877590037813561	
+1.9900000000000000	0.0510362143223593	9.8276370346207962	0.0543416248743181	0.0122645378288980	0.1661173229849053	0.1292355440210876	
+1.9910000000000001	0.0768899766616165	9.8342767555395252	0.0362101221936076	-0.0280768974868831	-0.1454411280008939	-0.1522813500980759	
+1.9920000000000000	0.0776785542983162	9.8259000002247383	0.0468942989486148	0.0867859708731088	-0.0071215677509139	0.0865872015291922	
+1.9930000000000001	0.0620146795723900	9.8450258282375032	0.0418109158194901	0.1455401254590123	-0.0557871727758948	0.1654674177252753	
+1.9940000000000000	0.0665442464855846	9.8303864593673165	0.0225656794864635	0.1751031260744534	0.1807070010785769	0.2411380588762684	
+1.9950000000000001	0.0623024624026346	9.8300694084230873	0.0569161348116544	-0.0860854701491092	0.1446837141760816	-0.0220867163043994	
+1.9960000000000000	0.0570209066005392	9.8342091248775727	0.0436132224603827	-0.2890234234177760	0.2162211148281028	0.1787226454488104	
+1.9970000000000001	0.0751221528007344	9.8232329560154863	0.0435531000948833	0.1750446899896363	0.2155456347722792	0.1814181602145410	
+1.9980000000000000	0.0711645254068634	9.8554929082620735	0.0413341532873714	0.0122396280238476	0.0088001380475905	0.1521026448103536	
+1.9990000000000001	0.0767870173144451	9.8316734789983489	0.0376349433838042	-0.1120286965852684	-0.1130191254460598	0.0931267575437251	
+2.0000000000000000	0.0562453526314453	9.8317984779753544	0.0250660966277596	0.3940209880437789	0.3987953570787178	0.3578042062715538	
+2.0009999999999999	0.0779634321972242	9.8277105229155186	0.0338632265671733	-0.0068545910246029	-0.3032988749623690	0.0196270132454548	
+2.0020000000000002	0.0929407605152066	9.8464842237365513	0.0543266354462270	0.0256246764463274	3.1980818872950518	0.0357603248875416	
+2.0030000000000001	0.0538412942379633	9.8188343414401782	0.0549815080989852	-0.0215633355734848	3.3125953024238481	0.1903439746933341	
+2.0040000000000000	0.0518540019199756	9.8069979587453737	0.0466329860197699	-0.0830590467777988	3.5005188467768238	0.2602391540492838	
+2.0049999999999999	0.0620920359085751	9.8254743834702349	0.0207837561819861	0.1143001213471763	3.0015209571708397	0.5302262504431977	
+2.0060000000000002	0.0544449967930189	9.8191073173511505	0.0362430945544589	0.2667199671643105	3.0852998960794276	0.1757732172581749	
+2.0070000000000001	0.0524690689345860	9.8290351180951649	0.0297657729430820	0.1858088043870257	3.1615234270253358	-0.2188316504002832	
+2.0080000000000000	0.0557910577524735	9.8312227424350986	0.0279325598578243	-0.2525161531145190	3.0730218045622695	-0.0548658926746222	
+2.0089999999999999	0.0664089280855292	9.8262134115007811	0.0478120168757012	-0.0515507055268456	3.0268337320823790	-0.0690639862469304	
+2.0100000000000002	0.0517319488742197	9.8255976086838608	0.0052145945507441	-0.1730645362442645	3.2627246527758529	0.1620396189090525	
+2.0110000000000001	0.0378628841449926	9.8216625047018091	0.0304126796513034	-0.0871968462773493	2.9689277450358635	0.1187010039182290	
+2.0120000000000000	0.0397237911364031	9.8276365017524583	0.0336902850631128	0.2848290497530687	3.2058031874982316	0.2841152194393924	
+2.0129999999999999	0.0815175696089568	9.8443036960081027	0.0343682217640757	0.0831481762908516	2.9242048129620657	0.1500157268641369	
+2.0140000000000002	0.0682367241626550	9.8264953292490826	0.0488409400673528	0.0641337743339432	3.3037541357799163	0.1180631326529862	
+2.0150000000000001	0.0632056997234085	9.8239264594037525	0.0421212997940685	-0.0916625152890740	3.2336317374215482	0.1077171187735249	
+2.0160000000000000	0.0680090971377024	9.8069854562337202	0.0431037401085603	-0.0764195692783267	3.1317248882963917	0.0105156368954001	
+2.0169999999999999	0.0543887964025773	9.8236995718589224	0.0386416805293615	0.1597235678709448	2.9190587642296522	0.1279874128206431	
+2.0180000000000002	0.0881771515486660	9.8086260464339574	0.0380134383335476	0.1601512548674765	3.1579102745525889	0.1365835535252084	
+2.0190000000000001	0.0551945476695424	9.8408095297562657	0.0252036607825685	0.0675554167168733	3.3452418725944923	0.2200068708070583	
+2.0200000000000000	0.0655686104985689	9.8408541047963194	0.0331003921446017	0.1286347740565285	3.1562133925923179	-0.0539013177178030	
+2.0209999999999999	0.0748700161509816	9.8044018416503498	0.0447899201375476	0.0700158518149135	3.0476733785758929	-0.2086068978129135	
+2.0220000000000002	0.0881852728919938	9.8258630581206035	0.0346706908850786	0.0245793502509289	3.2936785237350175	-0.0123128075334030	
+2.0230000000000001	0.0696266970203511	9.8266182731976812	0.0381464247899830	0.0045630165999643	3.3823437851359301	0.2164072853598621	
+2.0240000000000000	0.0572103853891045	9.8372613487985490	0.0390013250733249	0.2187783446226594	3.1201782537573948	0.0513450620965819	
+2.0249999999999999	0.0809182304667171	9.8050647170382668	0.0595968546504348	0.1999360423386986	3.0414098417570137	0.1434468159905772	
+2.0260000000000002	0.0375964786669283	9.8064985259525983	0.0552725779474179	0.0028619512415268	3.1063204581012718	-0.0528299493777096	
+2.0270000000000001	0.0509922073127808	9.8246398891793643	0.0327130938635105	-0.1076855990471920	3.1314955577943886	-0.0533737438015564	
+2.0280000000000000	0.0447864589906693	9.8186401350346060	0.0471239882416038	-0.0961086456881913	2.8702224406196541	-0.0399203627374192	
+2.0289999999999999	0.0547104634669498	9.8341425221772578	0.0182719124605890	0.0307297949598168	2.9852223329842924	-0.0229880907543601	
+2.0300000000000002	0.0757803073426914	9.8278371530884918	0.0386564838237552	0.4897300080280846	2.9985782219429891	-0.0201403254892280	
+2.0310000000000001	0.0629941055796970	9.8297406172279427	0.0416878245022863	-0.0950138849273551	3.0735899894033336	0.1187119167039487	
+2.0320000000000000	0.0573991570008402	9.8223693548717801	0.0508883269198240	0.0806452039225809	3.1040661310216349	-0.0788394266338880	
+2.0329999999999999	0.0519307457991953	9.8405353266323417	0.0543439669703789	-0.0608882979994356	3.0300653624171225	0.3785704112232685	
+2.0340000000000003	0.0525473751368187	9.8204457851727032	0.0437115985294737	0.0085414604605515	2.9840499792594524	0.0367633368960697	
+2.0350000000000001	0.0673988228168680	9.8272367895260189	0.0438151998024914	0.0465267623150246	2.8844297355591695	-0.0064202278034828	
+2.0360000000000000	0.0547421294614427	9.8349422391428529	0.0219995951494692	0.2053801547040244	3.2037782448692909	-0.1379328946966534	
+2.0369999999999999	0.0663172429526246	9.8389912516753704	0.0183200761024354	-0.2574946370056492	3.2499620183416655	0.2120407523990740	
+2.0380000000000003	0.0527243535500080	9.8332089911378198	0.0228809474883701	0.1096011429797788	3.1262681519827602	0.1177468245526866	
+2.0390000000000001	0.0651760271393166	9.8143103505549405	0.0412224260683857	-0.2452970454116932	3.5059121339984856	0.1059080541069395	
+2.0400000000000000	0.0596760925705792	9.8287650979658121	0.0542918684696396	-0.0648863599913706	2.8427478769780845	-0.1199179255954874	
+2.0409999999999999	0.0530336112945020	9.8462828716967223	0.0308992188248374	0.1800903378754216	3.1040832973903241	0.2500749859388422	
+2.0420000000000003	0.0725231157657393	9.8145825789148038	0.0420954564968527	0.0209225259541531	3.0077991008949896	0.1634996204334071	
+2.0430000000000001	0.0686416368265602	9.8607370676772703	0.0478532337757922	0.0241875702730178	3.1554739882099878	0.1019679935080997	
+2.0440000000000000	0.0736867416136634	9.8300807185229573	0.0518708762159650	0.2806144565795204	3.0110862999389774	0.0607475626138806	
+2.0449999999999999	0.0546253253546626	9.8044666929986217	0.0312984207821203	-0.2425134538953307	3.0851381278719723	0.2290172759177694	
+2.0460000000000003	0.0636029852237775	9.8431802722077677	0.0424407145814925	0.1291841206785969	3.1329393321773487	0.1534007316010461	
+2.0470000000000002	0.0644979351732693	9.8348553027423122	0.0397069094151661	0.0107882740000549	3.3198491788464537	-0.2079130888001423	
+2.0480000000000000	0.0527328217655348	9.8087377976875612	0.0475534423240224	-0.0606505791554314	3.4525971805909164	0.1577685310516133	
+2.0489999999999999	0.0562808366818287	9.8145678825298308	0.0076131750873343	-0.1429511430551244	3.1023549543535700	-0.0048518558382920	
+2.0499999999999998	0.0744739932019611	9.8236867085004107	0.0466025400770900	-0.0659392596744876	3.0591199619557696	-0.0975552735860142	
+2.0510000000000002	0.0435063833903987	9.8056278294824324	0.0490311026296376	0.1555713674046409	3.1120134082600761	0.0568008755022859	
+2.0520000000000000	0.0727532349290395	9.8077371227713996	0.0434686540954250	0.5635416270606444	3.2188954765854625	0.1732757269909568	
+2.0529999999999999	0.0589180315299382	9.8450085806678551	0.0142769989140104	-0.2936938167867343	3.0337924754110017	0.1421651062182883	
+2.0539999999999998	0.0596341606459847	9.8101105204131933	0.0676206472976185	-0.2570432944532020	3.2210711022626533	-0.0536581300540703	
+2.0550000000000002	0.0662621934586856	9.8223668854879929	0.0439339246650359	0.0706924338496929	3.2572738461568385	0.2019533131724258	
+2.0560000000000000	0.0755358185672697	9.8418022885649759	0.0388844332999845	0.0035423215656299	3.2245015981514449	0.1296362011655817	
+2.0569999999999999	0.0823575114370708	9.8187656557055156	0.0190277199146228	0.0142633932495389	3.2541281527745864	-0.0115327001556320	
+2.0579999999999998	0.0374735297514157	9.8384036558854753	0.0160265335909904	-0.1474179978847867	3.1976343091056627	-0.0127107664040428	
+2.0590000000000002	0.0581134160279817	9.8431340548669954	0.0277936300419637	-0.0407145217670193	3.1098023543354070	0.0861997938033189	
+2.0600000000000001	0.0741706153447221	9.8294280199778541	0.0238045786587626	0.0925433741756421	2.9547333598712462	0.2442400425516509	
+2.0609999999999999	0.0725759864987896	9.8256382653419720	0.0249505372904526	-0.0864123030117789	3.1445825327123869	0.1279522352864685	
+2.0619999999999998	0.0799704204098545	9.8397586132231005	0.0422907961838654	0.2614321141193758	3.2222616185695561	0.1962354128876250	
+2.0630000000000002	0.0546350195038233	9.8314252971003828	0.0317357464677186	0.1607252631674220	2.8388299227549196	-0.0991269209692861	
+2.0640000000000001	0.0502221797691677	9.8401346397526108	0.0354840783666947	0.0775080485944104	3.1465364283245290	0.0269152573989297	
+2.0649999999999999	0.0587016877638140	9.8113816326780867	0.0532214881246173	0.1546898303820398	3.1493424731017727	-0.1286026819513992	
+2.0659999999999998	0.0536619189346424	9.8132198611691273	0.0331904532240022	-0.0519721640012482	2.9285772598996083	0.1365247110806866	
+2.0670000000000002	0.0600960228678218	9.8425084242406840	0.0393885189988308	0.1243667882057864	2.9979404791622639	0.1872395133335743	
+2.0680000000000001	0.0772108028816237	9.8304153790497040	0.0350022891639514	-0.0893305031758405	3.0141132476486323	-0.1984117075910819	
+2.0690000000000000	0.0608533988835485	9.8153996166380537	0.0523728040234512	0.1336723100980172	2.9600884197064765	0.1034575888470388	
+2.0699999999999998	0.0763166846167279	9.8175006506693219	0.0342801596628886	0.0289895056852436	3.3375605557265544	0.1675976135212535	
+2.0710000000000002	0.0506250479007235	9.8390197305358882	0.0203606996040278	0.0219535726237783	2.8881519661789006	0.2849511131739781	
+2.0720000000000001	0.0536521897385043	9.8238389468787481	0.0274654722019023	0.0350446631804684	3.2745500431925789	0.2421791226387828	
+2.0730000000000000	0.0509818604890122	9.8534944365103208	0.0347300003013723	0.3475610223255846	2.8948327673997580	0.1331782128452694	
+2.0739999999999998	0.0358266317662317	9.8273073048383033	0.0379320825520276	0.0847299430303419	3.0874147500110039	-0.2538056447380795	
+2.0750000000000002	0.0652214096281034	9.8171406534798553	0.0386969410307341	0.0462735307171434	3.1028883987209630	0.2252523623554467	
+2.0760000000000001	0.0663143521881297	9.8284232424920539	0.0439240614504944	0.1857461261257636	3.1295830255065074	-0.1494690051735829	
+2.0770000000000000	0.0572198277063180	9.8394557909411695	0.0264560055457647	-0.0586892832951051	3.1518530972835417	0.1891206924377639	
+2.0779999999999998	0.0582798382019797	9.8394767668180112	0.0325401157999848	0.2675693317265880	3.1522734636652023	0.2427397850700429	
+2.0790000000000002	0.0459589171471918	9.8174019066283869	0.0329894034660489	-0.0056147561036900	3.2346370576615482	0.1739820237594608	
+2.0800000000000001	0.0622958320250685	9.8303170998163445	0.0353360096483072	0.1878009978078063	2.9676582888059762	0.3203677459491811	
+2.0810000000000000	0.0364285384651386	9.8182495533044740	0.0155507358586473	0.0474108513131762	3.1534679094676861	-0.0282127586290148	
+2.0819999999999999	0.0618349641882876	9.8252288106496657	0.0306803519101838	0.1252569350802814	3.1485134743985772	0.3067391706208757	
+2.0830000000000002	0.0543453339658019	9.8260956309698138	0.0365363463619955	0.1834696561309134	3.1669524680270560	0.2021558718447170	
+2.0840000000000001	0.0483592372455724	9.8336581414844275	0.0281713243095558	0.0883799870641364	3.4582487386970566	-0.0941553370831905	
+2.0850000000000000	0.0337545716206357	9.8358264126087942	0.0434473768432713	0.3587191779675925	3.4588975661506769	0.0144798342698254	
+2.0859999999999999	0.0580740304391746	9.8215832568713122	0.0279713556535549	-0.1587361766039031	3.0194500388386305	-0.0272194554657345	
+2.0870000000000002	0.0361492018542476	9.8252000239156878	0.0448515324614294	0.0343471783643375	3.1440155334852333	-0.0669651131442634	
+2.0880000000000001	0.0564352279560794	9.8343384574161359	0.0444716989808455	0.1650391120717915	3.1916205815806151	0.1206773064954267	
+2.0890000000000000	0.0527411376424319	9.8164023456894949	0.0387563254924561	0.2962292965750879	3.2171549121523824	0.2326125346198386	
+2.0899999999999999	0.0540171062139269	9.8291522204469466	0.0510762537502107	0.0057706687418764	3.2181435578156128	-0.0894305800169675	
+2.0910000000000002	0.0689838279230764	9.8225134125675613	0.0439497391447625	0.1937163322148526	2.9659443040894273	0.2165316947376681	
+2.0920000000000001	0.0602650894451449	9.8424970141830244	0.0222267388257826	-0.0311774859051965	3.4110796418290672	0.0473405178373347	
+2.0930000000000000	0.0539764254003643	9.8274954450351437	0.0557971897064976	-0.2027343557471356	3.2944294196721469	-0.0206577485026024	
+2.0939999999999999	0.0470469468968612	9.8338881135544991	0.0390950732033048	0.1509701761658526	3.1579307304339443	0.1052026223641994	
+2.0950000000000002	0.0437369315822585	9.8303238211007749	0.0348769798041998	0.1221830388987830	2.9879882165780609	0.3571071684815628	
+2.0960000000000001	0.0542160668162941	9.8290959174792043	0.0540693795622265	0.0012794776032215	3.3792283735941933	0.1150294077782458	
+2.0970000000000000	0.0635006259704290	9.8332117088255053	0.0346509603961585	0.3226831275003410	3.2101514240568618	0.0391903014582685	
+2.0979999999999999	0.0467618286437823	9.8297681553324328	0.0431681831057642	0.0835486390765987	3.1905896126280466	0.1482672871526449	
+2.0990000000000002	0.0571336947154585	9.8130493957869458	0.0342208096252396	0.1316658296833015	3.1623973866315991	0.0762870985953485	
+2.1000000000000001	0.0532016497921422	9.8337991896327193	0.0277982917201637	-0.0003703371706763	3.0359111377259378	-0.0212782261162279	
+2.1010000000000000	0.0729937943954672	9.8567202941378760	0.0552944524198905	-0.1890014462227369	3.1688430226700945	0.0864084157408327	
+2.1019999999999999	0.0461898424996540	9.8142849141473292	0.0370858640564490	-0.0867401657530391	3.0877422602284206	0.1640442995828844	
+2.1030000000000002	0.0674627239455279	9.8262336427501094	0.0259257165881788	0.0700931153206656	3.0915524136000569	0.0990711854922427	
+2.1040000000000001	0.0738636497716637	9.8191284566087038	0.0605076339249095	-0.1056954540879538	3.1416209698288680	0.1509609901978151	
+2.1050000000000000	0.0524862906683647	9.8279816206490356	0.0532098749210888	0.1705559785310691	3.1987870499984954	0.0386638948878225	
+2.1059999999999999	0.0553700284763049	9.8164489457885420	0.0341046377092074	0.0327487688328011	3.1920275593969096	0.0907973599632586	
+2.1070000000000002	0.0628447784042280	9.8353500466947139	0.0363048026213749	-0.0085356038621547	2.8666134049250300	0.0548191726810508	
+2.1080000000000001	0.0422871701344843	9.8241514237491998	0.0274550290819487	0.1131183667839691	2.9504448335792501	0.0778846055081178	
+2.1090000000000000	0.0238357275833631	9.8318490682216364	0.0474833578678116	0.1122616939950861	2.8445708323478147	0.1703343916010803	
+2.1099999999999999	0.0314676426290242	9.8310748206379763	0.0273376910995109	0.1272039097411354	3.2082259217924167	0.2396418211928692	
+2.1110000000000002	0.0542494936235576	9.8213948436798884	0.0390247881072529	0.2534995128545757	3.3357464639827041	0.0351356149493377	
+2.1120000000000001	0.0520593535800683	9.8262934446008448	0.0273032680239467	0.3381050824060287	3.1273674778898051	0.2718535957727132	
+2.1130000000000000	0.0673069918432168	9.8315822604074157	0.0167764052982281	-0.0352546975890147	3.0920967619021349	0.1725966659005084	
+2.1139999999999999	0.0567342908921091	9.8434797284273223	0.0457627567850208	0.1508382870215516	3.3197106483996950	0.0719959405302180	
+2.1150000000000002	0.0674529737977375	9.8274327119811069	0.0349990353200750	0.1801084673339899	3.3621580548034684	0.0583439689585553	
+2.1160000000000001	0.0509729052865476	9.8272542093017012	0.0166103068755476	0.0432664286799819	3.0270956331488770	0.1796727869285218	
+2.1170000000000000	0.0562555150610752	9.8203255589907954	0.0354293156765049	0.3231571786575358	2.9309843283909198	0.1739890429679924	
+2.1179999999999999	0.0468897077884709	9.8479515436121687	0.0175191602092813	-0.1791677348283440	3.1378222412478518	-0.0832673903919081	
+2.1190000000000002	0.0478153107836988	9.8216031130749410	0.0467626059643831	0.1911310801574008	3.0539867612752594	0.2799418339102208	
+2.1200000000000001	0.0463380793779904	9.8199928254998632	0.0297098911865057	-0.0409387061137726	2.8660981396442882	0.0143331837537103	
+2.1210000000000000	0.0700430330165132	9.8114450635067030	0.0204661069296867	-0.0085336438188766	3.1986869173206522	0.1703228975537086	
+2.1219999999999999	0.0285803799254880	9.8264156636635107	0.0429779489149218	0.1319826442522634	3.0033515412867522	0.0847589328537110	
+2.1230000000000002	0.0454776248870145	9.8239339587108372	0.0207577695609565	0.1498426385697033	3.0531069443669310	-0.1179219104302244	
+2.1240000000000001	0.0564197339835731	9.8401912784423562	0.0184634706475119	-0.1074432258429400	3.0588206979172456	0.0453408495854648	
+2.1250000000000000	0.0501171531131037	9.8252845973529883	0.0460591792313331	-0.2638172504577795	3.1064151502486403	0.0182128697353319	
+2.1259999999999999	0.0511373372368884	9.8239636293324235	0.0389349785532425	-0.0565367206438037	3.0324015929485477	0.1464322919601372	
+2.1270000000000002	0.0855987734733495	9.8280886910202252	0.0353052548913866	0.2035451678026287	3.2037397197259416	0.0760308211984346	
+2.1280000000000001	0.0475335383284197	9.8301846089500451	0.0470252966300968	0.3185813619888749	2.9677035627738166	-0.0445252858884014	
+2.1290000000000000	0.0503282153430266	9.8411195641991558	0.0388372366421069	-0.1984404987042118	2.8261207646436848	-0.1945128204939421	
+2.1299999999999999	0.0665858905856465	9.8226685789038282	0.0373051723397166	-0.0527789559448535	3.2334636993812755	-0.0368860473906755	
+2.1310000000000002	0.0671165503289832	9.8156021500629382	0.0399364266075419	-0.1446234026732253	2.8804502336188937	0.2261844364990855	
+2.1320000000000001	0.0394452436040152	9.8176642439820743	0.0371156927427192	0.1584914060501346	2.9898374283437850	0.2964781092153060	
+2.1330000000000000	0.0473204519676444	9.8218532574106110	0.0673742323927696	0.2574739968369243	2.7571001279876834	0.0856435092901053	
+2.1339999999999999	0.0441292705001700	9.8279379650266954	0.0325425871102611	-0.0197373309675445	3.0160802640398900	-0.0210631297515809	
+2.1350000000000002	0.0430717088567051	9.8404372377757010	0.0261331982359566	0.1723625383126478	3.0880666617426575	0.1830629623023810	
+2.1360000000000001	0.0670587804749283	9.8167530478065306	0.0374320991361316	-0.0570670906495929	3.0160274617878891	0.1010489180587731	
+2.1370000000000000	0.0391764928786195	9.8167283260494393	0.0439472116017777	0.2058182331031121	3.0824221278465487	0.0254177557498677	
+2.1379999999999999	0.0591019523203519	9.8439308415226687	0.0420157601666494	0.2013557317067305	2.9843908322456123	0.0320888962099120	
+2.1390000000000002	0.0476299413139502	9.8220255964697056	0.0203582638483669	0.2428968036442855	3.1614494298668885	0.0373246125017737	
+2.1400000000000001	0.0447244253710235	9.8373700758955192	0.0377149573469892	0.1829982945591190	3.1945558385843382	0.1467710505859378	
+2.1410000000000000	0.0592245496783811	9.8460465022037074	0.0365236964702597	0.1690073859562560	3.3095174997736070	0.2000107406602295	
+2.1419999999999999	0.0466551388919201	9.8402012934308178	0.0488778277597497	0.0313665453816504	2.9615130823322082	0.3202705665537959	
+2.1430000000000002	0.0557927587549804	9.7968462890987311	0.0152593564155565	0.2513688524561045	2.8702824782674123	0.1005571510253108	
+2.1440000000000001	0.0438739605930954	9.8426393940384393	0.0087726078635942	0.1026841345103889	3.0245349333577272	-0.0425499933382452	
+2.1450000000000000	0.0417006296764409	9.8251698488648191	0.0328847567327065	0.0695069928726504	2.8922899848152812	0.2211329123773917	
+2.1459999999999999	0.0676554730416599	9.8262316821605094	0.0173963281917118	0.0236322318648434	3.1238897034672082	0.1040947672897882	
+2.1470000000000002	0.0380894020197027	9.8385306898789668	0.0524338721017442	-0.2274224195712501	3.1143985422650760	0.0215242836012140	
+2.1480000000000001	0.0500894708407778	9.8211177808930348	0.0386182317824506	-0.1258668239256102	3.1917827556630258	0.1160693035504160	
+2.1490000000000000	0.0546442747276245	9.8283994643169308	0.0404227763639786	-0.0379348188941968	3.3025810567140628	0.2729695736581690	
+2.1499999999999999	0.0369734659175156	9.8363600802277844	0.0047138118052311	-0.1420364666444815	3.2525408021964894	-0.0581317493416239	
+2.1510000000000002	0.0503941074112981	9.8459350865941797	0.0271677734214501	0.2320683808515237	2.7287600205952076	0.0662165185320136	
+2.1520000000000001	0.0515185516167391	9.8129311225434357	0.0074108914112602	0.0739294322608158	2.9361435601050747	0.1978725361591436	
+2.1530000000000000	0.0426878737189213	9.8203840757498835	0.0350724561727841	-0.0299800604901516	3.3226526055246048	0.0678913654630693	
+2.1539999999999999	0.0564146322087074	9.8302875540053982	0.0282943245842468	-0.2387737714687275	3.0913133282858354	-0.0342522305674489	
+2.1550000000000002	0.0471156393262512	9.8405212438872649	0.0283171284799768	0.0619959181900573	3.2265681172377607	0.4311844852850885	
+2.1560000000000001	0.0644899563564576	9.8087072919118565	0.0387093639537128	-0.1894381611511422	3.0856096964088637	0.2504981377347251	
+2.1570000000000000	0.0517270288773227	9.8336445168069577	0.0265345812626526	0.1843796536915299	3.1513998386283899	0.2740291954464134	
+2.1579999999999999	0.0442287444531399	9.8510836096833003	0.0259086101733356	-0.0290790280691015	2.9754200055025186	0.1490002478692787	
+2.1590000000000003	0.0406392596653073	9.8159991065143686	0.0172552857543264	-0.0175960316645842	3.0639329209005277	0.3867132014833437	
+2.1600000000000001	0.0513964024312927	9.8319171582038827	0.0422388792839116	-0.1259686783963385	3.1197596644283601	-0.1045666437121637	
+2.1610000000000000	0.0627181696269246	9.8178129568854402	0.0109735955151183	-0.0330142602442169	3.0194757457270240	0.0512943762765113	
+2.1619999999999999	0.0644997725793831	9.8130103779100128	0.0508234595545858	-0.1971417678131146	2.8392854747535883	0.0791425537031592	
+2.1630000000000003	0.0615976860582222	9.8253457752730498	0.0393369440496381	-0.1728455371189326	3.1129452660077606	-0.0739315249220914	
+2.1640000000000001	0.0469921901360892	9.8229078928624372	0.0347603011481817	0.1079695578391235	3.1708225657262483	0.0675470675749968	
+2.1650000000000000	0.0596065192225231	9.8226941283351206	0.0416218495109136	0.1140234053798811	3.0360949326144442	0.1004573855907703	
+2.1659999999999999	0.0397836595123541	9.8279749559960390	0.0189431487344688	-0.0358382612778581	3.1870035631854727	0.0725516146229920	
+2.1670000000000003	0.0306503441850299	9.8238753691207847	0.0330243654977132	0.0255533018696598	3.0664730008738195	-0.1719768512063018	
+2.1680000000000001	0.0494200036577046	9.8125190321767128	0.0529368700555791	-0.2651356343594927	3.2987275499487514	-0.2425708467690754	
+2.1690000000000000	0.0361310071428843	9.8220552062589608	0.0287042685581494	0.1915847460642565	2.9100986790598400	0.0939408723245962	
+2.1699999999999999	0.0332322723857372	9.8349989104194684	0.0082311787083067	-0.1727764637068522	3.2328871827236041	0.1239604563237892	
+2.1710000000000003	0.0387303655572389	9.8012047644045275	0.0274571906133430	0.1546433659871678	3.2135277728698153	-0.4052813806345680	
+2.1720000000000002	0.0601376269216809	9.8256825742582308	0.0385330050247946	0.2567978930293012	3.0463375123621299	0.0865262110437786	
+2.1730000000000000	0.0571933458825992	9.8031554530271006	0.0191558057197576	-0.0866080736152146	3.1660775939628358	-0.1143453836184650	
+2.1739999999999999	0.0412128567569870	9.8149666167730842	0.0345728547393972	0.0379338908124676	3.2722420543727697	-0.2777833931842698	
+2.1750000000000003	0.0510031379817795	9.8174832552231166	0.0261694757493631	0.1698500764788202	2.9367444783686913	0.1989110603695907	
+2.1760000000000002	0.0559123821445272	9.8129061172911509	0.0316821269554303	-0.0074089725357075	3.2091186535036025	-0.1342491170285769	
+2.1770000000000000	0.0458846853268979	9.8259861377511211	0.0193803691804707	0.0396760426894066	3.1561567916625224	0.1031994882880904	
+2.1779999999999999	0.0442919611577882	9.8013771909514915	0.0326431572569994	0.0275019949175459	2.7866524864328568	0.0845133430091895	
+2.1789999999999998	0.0421604889359929	9.8112584353341408	0.0211636659741170	0.0000856954669253	3.0748375929580192	0.2227178447219277	
+2.1800000000000002	0.0452936906558790	9.8454493342233196	0.0421188278287492	-0.2308361049189421	3.1654285133151783	0.0345519838635082	
+2.1810000000000000	0.0490713637361469	9.8080076263719906	0.0172914818595528	0.0087223376856000	2.9459857884679064	0.3063575797952702	
+2.1819999999999999	0.0439174726192416	9.8268314599484938	0.0432433560091864	0.1998229127935104	3.2813828461302883	0.0192121396841520	
+2.1829999999999998	0.0442204120156428	9.8297214877391532	0.0291906523298656	0.2315744107035315	3.1237384202557092	0.3067220683137927	
+2.1840000000000002	0.0311817805974923	9.8319372264293143	0.0465290000307711	0.1642580078383718	2.9877087097365447	0.3162948880515735	
+2.1850000000000001	0.0704631036158852	9.8250172997700762	0.0334151151100365	0.1738462587842765	3.2894612948916890	0.2138287103731917	
+2.1859999999999999	0.0487228335925618	9.8248408629070454	0.0354894856674757	-0.0198523611456241	3.3961675704586507	0.0637593749305956	
+2.1869999999999998	0.0442335724966299	9.8095102915478147	0.0392812573177333	-0.2365435374989019	3.1688102024648113	0.0913189003195206	
+2.1880000000000002	0.0539235112680766	9.8561890751127343	0.0141217344517908	-0.0029030357217389	3.2215433098239199	0.2238524074240385	
+2.1890000000000001	0.0429361594380592	9.8444689281421311	0.0310707167205037	-0.0513868899662780	3.1502518570421194	-0.0940057864733958	
+2.1899999999999999	0.0282929989640780	9.8281716592395245	0.0213355095491383	-0.0887603903723159	2.9662607058365094	-0.0011236849864518	
+2.1909999999999998	0.0649593737271846	9.8267209789041914	0.0311140253587019	0.0425891032481993	3.0899382233211501	0.1453987503594197	
+2.1920000000000002	0.0700040601042157	9.8143767779347701	0.0299623058960287	0.0977933312193690	3.4543372356667978	-0.2769494663070194	
+2.1930000000000001	0.0537499836895529	9.8153527415464072	0.0363927580938890	0.0059251272966727	3.1170063472628211	-0.0858631091913079	
+2.1940000000000000	0.0580616617427335	9.8387388907348523	0.0130796454323605	0.0140542279460874	2.8752136476778225	-0.0776679397101602	
+2.1949999999999998	0.0331218120581068	9.8316148735621240	0.0322706352547515	-0.0960615856233921	3.2670564007557985	0.1589093151254840	
+2.1960000000000002	0.0427751279268687	9.8372427297623481	0.0244506899346307	0.0777532927504875	3.1770740194261968	-0.1408896337889756	
+2.1970000000000001	0.0547635233882958	9.8293514900794179	0.0353795883609584	-0.1625437893271103	2.8575818107117112	0.0989019440355133	
+2.1980000000000000	0.0494523735757805	9.8250164330873666	0.0324040696207656	-0.1003277193489354	3.1215287073584008	-0.2290912187020677	
+2.1989999999999998	0.0537816250732532	9.8339366903608987	0.0209526359413433	0.2365771889785482	3.3882507478372497	0.1266486921375656	
+2.2000000000000002	0.0296815550191917	9.8335379748018674	0.0264039647212132	0.2110546387991228	3.2932631256843106	-0.2243162948731857	
+2.2010000000000001	0.0625013447436268	9.8293821115801201	0.0198009402597741	-0.0671933887763018	3.1423800168111997	0.0580139631673340	
+2.2020000000000000	0.0471400322062576	9.8079951177933040	0.0384294352687965	-0.0482977452442891	3.0436996086854231	0.2958272295744240	
+2.2029999999999998	0.0613556798414213	9.8051497157777963	0.0128893651479053	0.1402341568379048	3.3276477119840449	0.1428018504674501	
+2.2040000000000002	0.0543548204399229	9.8262066376954316	0.0183346390722763	-0.0133028577219286	3.2833504957829054	-0.0755721896748538	
+2.2050000000000001	0.0535038083171310	9.8162986368466694	0.0275189759249839	-0.0117690715862170	3.0383117145272123	0.0202778276841379	
+2.2060000000000000	0.0581909696368458	9.8246405010970062	0.0344617111122518	-0.1161558376119175	3.1789878588334504	-0.1127510374991956	
+2.2069999999999999	0.0489165460695212	9.8090163624146332	0.0301861013867821	0.2539497666605884	3.0505983281452376	-0.1945863302393604	
+2.2080000000000002	0.0621150827360195	9.8083758577601223	0.0299282665626137	-0.1005950823710210	3.1381009727772184	0.1048755634525223	
+2.2090000000000001	0.0581514324081773	9.8418085587840451	0.0244064852639125	0.0094228564640506	3.2420763209288288	-0.0160766615638887	
+2.2100000000000000	0.0489941043213002	9.8016650356796315	0.0263456222281429	0.2632016077347218	3.1614236186914728	0.2566863548036046	
+2.2109999999999999	0.0542545468498750	9.8287464204136228	0.0300535292775233	0.0616704212564256	2.8067884799425706	0.0178601863660230	
+2.2120000000000002	0.0303337049862084	9.8189466392873932	0.0335086344007934	-0.0379526789493403	2.9141660016035358	0.2574397853375686	
+2.2130000000000001	0.0396221374830187	9.8020719529063793	0.0268867509219689	-0.1329070859503833	3.3099414291841440	0.1941032750701880	
+2.2140000000000000	0.0466685396216852	9.8126358135953637	0.0165547814929551	0.0236420104496175	3.1352999237738164	-0.1665490636026386	
+2.2149999999999999	0.0548287329413359	9.8228719392348633	0.0399001045967411	-0.1953450978625785	2.9172868491102579	0.0466334797886381	
+2.2160000000000002	0.0328440310400265	9.8484255797450881	0.0296297612295963	0.1939022903869776	3.1368152715890232	0.0862623910383652	
+2.2170000000000001	0.0488545564234707	9.8322325522960128	0.0103580553650428	0.0011230813797514	3.0204446473342736	-0.0815777045760096	
+2.2180000000000000	0.0609071065843340	9.8436800384648446	0.0272107220277509	0.1819867562847320	3.1273634997034216	0.3697896893144650	
+2.2189999999999999	0.0266214134801973	9.8156239215358685	0.0446386991660566	0.2725666945790270	2.8027779354037552	0.4604074852906255	
+2.2200000000000002	0.0234055444420522	9.8190094702275594	0.0228138818407403	-0.0768670700151053	3.2281537882404381	0.1791722698357375	
+2.2210000000000001	0.0346476398625765	9.8349407855464541	0.0309296181114855	0.1192335692978828	3.1940065670375293	0.0825591985347661	
+2.2220000000000000	0.0644334864643186	9.8166705175404196	0.0235961768030868	0.0090617928441175	3.0275654961361402	-0.0248066717437530	
+2.2229999999999999	0.0534519128701465	9.8267334003925484	0.0453432639924960	0.0642568249069937	3.3039881024444586	0.0502331510399303	
+2.2240000000000002	0.0636224564289621	9.8415206409926625	0.0432878759841612	-0.0803903849475548	2.9916614151165759	0.2340827346426406	
+2.2250000000000001	0.0392656083350431	9.8374225673800346	0.0222315361059836	-0.0081008856404035	2.9914689901789075	-0.1930062413683513	
+2.2260000000000000	0.0251220317924554	9.8409590829035647	0.0283341556891635	0.1848440959471273	3.2397305975873216	-0.1301660183334895	
+2.2269999999999999	0.0135813315940408	9.8289550136639061	0.0188837063464315	0.0646389670191588	3.2377034826522126	0.0413349521504426	
+2.2280000000000002	0.0538761019545681	9.8327828741079681	0.0200540263553192	0.0879991725943412	3.1558104859177547	0.2109423709156009	
+2.2290000000000001	0.0384065818734706	9.8497588586663518	0.0264976762756588	-0.1738029876294983	3.1397122841569449	-0.3102122762743194	
+2.2300000000000000	0.0403611713942697	9.8073797621491963	0.0314937302988580	-0.1669164202540804	2.9747331929754557	0.1655977776498241	
+2.2309999999999999	0.0390046972291302	9.8393094202888260	0.0136953695756825	0.2249364441922797	3.0849733011896294	0.2883926895035112	
+2.2320000000000002	0.0401359523050012	9.8270986313898447	0.0199963975431773	-0.0214429198771500	3.0049411021219128	0.1620959431534589	
+2.2330000000000001	0.0313299639207850	9.8199480137508530	0.0078706014834030	0.3381542334452562	3.0091993183463255	0.0778345187841479	
+2.2340000000000000	0.0550243695204754	9.8057091146128901	0.0165384674906224	0.0999272565212089	3.2021429785435789	0.1665922941843314	
+2.2349999999999999	0.0333678700384229	9.8342834574381506	0.0329739086567966	-0.1592215331642952	3.1017993462733990	-0.0895241611304753	
+2.2360000000000002	0.0480222242909374	9.8222444947100325	0.0054834267581420	0.2482203210413456	3.2368822926251357	-0.0534260303525292	
+2.2370000000000001	0.0633843157417278	9.8159358511025516	0.0340362204467528	0.4229835123486286	3.3723852637199925	0.1061319339127000	
+2.2380000000000000	0.0509302641877345	9.8070553594516312	0.0205303806242699	0.0754792693091684	2.9905075982529135	-0.3136632835219539	
+2.2389999999999999	0.0259195823006030	9.8362367108638349	0.0305820425470207	-0.0424798772668652	3.0630607131159175	-0.1507205568156237	
+2.2400000000000002	0.0136193347951144	9.8338932561709473	0.0265037985881107	0.2134899539670943	3.1489961228648986	0.0717975656185527	
+2.2410000000000001	0.0518737320892671	9.8383995789082697	0.0544470073267480	-0.1335228897254354	3.0316159208529796	0.3149153125323338	
+2.2420000000000000	0.0367779456672951	9.8488793651119337	0.0251221307573768	0.0026363922037954	3.1762500097532111	-0.2819634731298911	
+2.2429999999999999	0.0494673334778743	9.8293481893341976	0.0112458365158776	-0.1205543700880213	2.9041504442591548	0.1211978401449747	
+2.2440000000000002	0.0488686815788331	9.8178137885221020	0.0378994380048642	0.0946480373236682	3.0939914491594789	-0.2246211767668789	
+2.2450000000000001	0.0120844120232809	9.8324342770091437	0.0357720826539599	0.1766379929009943	2.6969197343106130	-0.0322682267186996	
+2.2460000000000000	0.0466368637008079	9.8226363685876930	0.0374481416157888	0.0811672047468911	3.1191761091323693	0.1962144797307680	
+2.2469999999999999	0.0441078422664736	9.8414181725167822	0.0208608785888322	-0.2360237086579193	3.2973182643552383	0.1068807610328696	
+2.2480000000000002	0.0377359857646731	9.8236133142270567	0.0208199018838925	-0.1332287801961171	3.2046592919068209	-0.3054635423426241	
+2.2490000000000001	0.0613235487218919	9.8235417983548778	0.0392128288729069	0.0323021168545752	3.2151909697179915	0.1740406319683476	
+2.2500000000000000	0.0688876221065444	9.8164790755188314	0.0186176829456217	0.0213566063857302	2.9303194769133727	0.1074972045003712	
+2.2509999999999999	0.0493708979186561	9.8427478477027037	0.0280933857079141	0.0082005008842540	2.9911943006404473	-0.0543403699051268	
+2.2520000000000002	0.0491358268418038	9.8136259966259018	0.0445079172043436	0.4889794686181921	2.8911046161085672	0.0816809257949686	
+2.2530000000000001	0.0300059727338150	9.8129299796344931	0.0285521159448113	-0.1048364638348668	3.1883288569052302	0.0529562196567516	
+2.2540000000000000	0.0643886063298533	9.8267551007205842	0.0399881123814642	-0.1218178775751532	2.9700055430781145	-0.0972567972051309	
+2.2549999999999999	0.0456764249704948	9.8289503689886963	0.0195687066861795	-0.0212339197942122	3.0120952448254363	0.2944368705405844	
+2.2560000000000002	0.0447066203273073	9.8285045983392578	0.0236832380370074	-0.1598792101564959	3.1548197824133162	0.2927018076287045	
+2.2570000000000001	0.0297911225478360	9.8354151650348367	0.0339161298202944	-0.0968245103774968	3.0679046153285956	-0.0338060740149661	
+2.2580000000000000	0.0172125703244745	9.8117800246072697	0.0286845091791123	0.1400013045660000	2.8255864734275651	-0.0426278385913543	
+2.2589999999999999	0.0554556400658365	9.8277279155280173	0.0266380313126046	-0.0802046239497640	3.1254190997093345	-0.2122102332602235	
+2.2600000000000002	0.0530678321095237	9.8425394313451111	0.0170249869393178	-0.0774777948916801	3.0272272911614477	0.1775475283300393	
+2.2610000000000001	0.0524501111233559	9.8280738526401308	0.0294162451794369	0.3448167602816924	3.1452117366759249	0.1953540371045038	
+2.2620000000000000	0.0244291056359408	9.8346384408491119	0.0413721963054118	0.0806545489311900	3.0601400515204635	0.0810807935368352	
+2.2629999999999999	0.0461724136043234	9.8219984462309071	0.0652557257537318	-0.0767331273312268	3.1157280733700530	-0.0282244990497127	
+2.2640000000000002	0.0432955142610678	9.8295596464892832	0.0335081880196112	0.2227142928854590	3.0257652163285860	-0.0186885824274931	
+2.2650000000000001	0.0409052644470084	9.8248710213787032	0.0168798328429466	0.0548532628027340	2.8624032521677725	0.1190409374156376	
+2.2660000000000000	0.0424334495408675	9.8189129383658518	0.0297783719213022	0.0555863470143671	3.0445678368672318	0.1699855619244095	
+2.2669999999999999	0.0600955971893090	9.8386717016408660	0.0377915384302184	0.1467563337423759	2.9048703465400294	0.3080315273381178	
+2.2680000000000002	0.0384626268513870	9.8350120705790545	0.0186781522629948	0.2164510064795297	3.3093163118950333	0.0580492694080067	
+2.2690000000000001	0.0467532116476185	9.8454425261676040	0.0224608153940959	0.0842545477471211	3.0637298319372386	0.1623495597722927	
+2.2700000000000000	0.0213475020351599	9.8048613073465916	0.0124763678863326	0.3220686687638072	3.0379088514130252	0.1785053629756795	
+2.2709999999999999	0.0258112231735372	9.8168796306124797	0.0175252607119355	0.2726087786493450	3.1857206186350808	0.1620730811283033	
+2.2720000000000002	0.0378418072269350	9.8465406809522307	0.0121089875669824	0.0413840215038350	3.2404069794404085	0.1351446746671390	
+2.2730000000000001	0.0574801970100417	9.8159895395731915	0.0218300880076585	-0.0677429235473697	3.0139642971104670	0.0771875962416175	
+2.2740000000000000	0.0412229880494628	9.8428276158452093	0.0136771422884925	-0.1004316512727510	3.1777389357516608	0.1560575188991303	
+2.2749999999999999	0.0221720979360841	9.8297367895687096	0.0441216409233745	0.0905503123412177	2.8595780632659507	0.1014595505936516	
+2.2760000000000002	0.0501771266009923	9.8324627373362912	0.0168442318527609	0.1056369905811542	3.3151405022970764	0.1603515908817391	
+2.2770000000000001	0.0300527253948000	9.8145899408185269	0.0190441577116350	-0.1636967136148078	3.0560624289909559	0.0257891295087376	
+2.2780000000000000	0.0547113597776336	9.8386547571902785	0.0325685281129650	0.2245790345882869	3.0804360034264451	-0.0604829675069795	
+2.2789999999999999	0.0521179635424868	9.8202026816381824	0.0262488454773860	0.0380648436257264	3.1394696027823383	0.1149801959695530	
+2.2800000000000002	0.0300653988193486	9.8311117972260753	0.0418653516516999	0.0025445576980063	3.0285071025939203	-0.1057898154535790	
+2.2810000000000001	0.0478793229174093	9.8206077091699004	0.0334448685713954	0.1464216468498384	2.7889743059416707	-0.1750252186271526	
+2.2820000000000000	0.0485841205039089	9.8255995525282902	0.0240461674783458	-0.0285823451391457	3.0898060535481640	0.4248721960223811	
+2.2829999999999999	0.0224432377696842	9.8366166515143494	0.0327356069524358	-0.0291368104708038	3.1966803925449456	0.1821620642832316	
+2.2840000000000003	0.0308716603356303	9.8371910187977445	0.0206025442363430	-0.1924324810276511	3.1570175837980270	-0.0324399758153029	
+2.2850000000000001	0.0502630063857482	9.8319552062424158	0.0213579828135558	0.1854684625191590	3.1631215404699411	0.0614389603243631	
+2.2860000000000000	0.0474635732298961	9.8275894369985917	0.0338015223181948	-0.0038265638817062	3.0582462690751537	0.0226820211685712	
+2.2869999999999999	0.0545667584962225	9.8216975509561149	0.0110517147206743	-0.1911790990911968	3.1224708000471648	0.0972661608571651	
+2.2880000000000003	0.0409186669686667	9.8040443599362312	0.0145297260533587	0.0398776417729242	3.3537087740520373	0.3300090909158090	
+2.2890000000000001	0.0236813536828757	9.8256042633807521	0.0100384718773944	0.1177214181794033	3.0410357002130284	0.0681598296458632	
+2.2900000000000000	0.0347805461954127	9.8166132121574297	0.0269081984976690	0.3033167792066263	3.4600608192576456	-0.0123883181866044	
+2.2909999999999999	0.0455695271196659	9.8203715488260297	0.0325455095183704	-0.0733831907509162	2.9725001672741858	0.1300030264475980	
+2.2920000000000003	0.0467142749054362	9.8359342008769080	0.0350857218971667	-0.0794856536785227	3.0689836570973954	0.0379364779170459	
+2.2930000000000001	0.0279238374045012	9.8263779579118662	0.0389430700068229	0.0276984371646613	3.1374837600288998	-0.2720421266522830	
+2.2940000000000000	0.0337056665286209	9.8189001314508317	0.0287436959303665	0.1597356254593135	3.1341979441156202	-0.0323138433743471	
+2.2949999999999999	0.0463420960955945	9.8352299723978494	0.0332686009742093	0.2865613749510373	2.9592947115335435	0.0996811656606331	
+2.2960000000000003	0.0526258643125006	9.8297787928465485	0.0401172121661632	0.1722863546409648	3.0075241992945974	0.0843731185571330	
+2.2970000000000002	0.0427865203827823	9.8294415200876042	0.0289187459838192	0.0218996902846836	2.8711544690653565	0.0425275678777412	
+2.2980000000000000	0.0502994723789525	9.8237144320720802	0.0367130294470273	0.0694279246286156	3.3491628897013137	0.0960319213865567	
+2.2989999999999999	0.0475191088457509	9.8301967861904398	0.0406585275413658	-0.0851531757309685	3.2814280218184084	0.1934601151721978	
+2.3000000000000003	0.0363417176439857	9.8208677198125010	0.0237771415708138	0.2529155787902196	3.2726701280731323	-0.0072907904339742	
+2.3010000000000002	0.0592179527943127	9.8183940324802119	0.0256809579947613	0.1622179893017001	2.9911290516329103	0.0117250349684719	
+2.3020000000000000	0.0226971974472199	9.7956497920850083	0.0388981471694574	-0.0472346283306283	3.1951838959855801	-0.0270283015790335	
+2.3029999999999999	0.0398532478327461	9.8395561373044522	0.0315484215057650	-0.0741228472274772	2.9698356688885155	0.1160560141046635	
+2.3040000000000003	0.0175037039281459	9.8344970956524289	0.0329908302929879	-0.2669022800299621	3.0240012186974989	0.2284630783627583	
+2.3050000000000002	0.0473447204048148	9.8297020049749495	0.0106973570725207	-0.1126509644062125	2.9638195499600766	-0.0039768491724323	
+2.3060000000000000	0.0580292755395485	9.8036730697580374	0.0138800704431688	-0.2495923836768960	3.1602706652640977	-0.1348332901572258	
+2.3069999999999999	0.0297696414285512	9.8261821755563155	0.0324055933361659	-0.2649458555563347	3.0557373359282876	0.1171597477892213	
+2.3079999999999998	0.0473698216711618	9.8187271868266279	0.0152243934055453	0.2433038284545937	2.9365504456302207	0.0259942473715147	
+2.3090000000000002	0.0293493491450692	9.8441086795351325	0.0468813482170844	0.1349320368655278	3.0487704071003905	-0.0433825349119527	
+2.3100000000000001	0.0396883719909168	9.8407502868746288	0.0190986325917388	0.1146255136179650	2.9808560401346278	0.0849289875512363	
+2.3109999999999999	0.0225822302815005	9.8359925832343116	0.0258135415784199	-0.1372784520025319	3.4482820280803113	-0.1430773924657144	
+2.3119999999999998	0.0322824982082622	9.8186606300418582	0.0177346205077002	0.1310919560281893	2.9936558531678572	0.0773911529618206	
+2.3130000000000002	0.0288307311424743	9.8370294828631533	-0.0010361888904660	0.0054376365617203	3.0597009464596785	0.1231877365868263	
+2.3140000000000001	0.0561928938119476	9.8344019934384921	0.0262175593155353	-0.0294648412623583	3.0546380721157167	0.0065247182513919	
+2.3149999999999999	0.0492487782030647	9.8186430037783694	0.0130086460698824	0.2355928225855607	3.3160654055042418	0.0870335276696133	
+2.3159999999999998	0.0336966169931067	9.8055647023055830	0.0376963470558036	0.1096198601702578	3.2918419363796363	-0.1510030973021384	
+2.3170000000000002	0.0530464235042954	9.8160407816441992	0.0243519322515123	0.0186759238210015	3.0675638322354648	0.2627725833326866	
+2.3180000000000001	0.0169811444115656	9.8060065178108822	0.0056463673997946	-0.0009836991529296	3.1778839349367072	0.0828792747844530	
+2.3190000000000000	0.0567170816495210	9.8100532809396643	0.0173078265405346	-0.1484632685133314	3.1267361972153966	0.1199072483928081	
+2.3199999999999998	0.0439927638034843	9.8118773611374159	0.0237656352182789	0.1028760494127680	3.1536976463584985	-0.1124558029751198	
+2.3210000000000002	0.0259044515221552	9.8272232908674599	0.0418795245783226	0.0782883811865498	3.0398351006151731	0.3284596715074110	
+2.3220000000000001	0.0486061575351511	9.8108735631209676	0.0264104970015431	0.0735400600621815	3.0312588811780223	0.1837812530820326	
+2.3230000000000000	0.0250056597941948	9.8288475609167936	0.0406805229125431	0.0296776651077278	3.1235113932926231	0.0326037392159562	
+2.3239999999999998	0.0329288829485089	9.8117013037579017	0.0040518049039881	0.1905267041378022	2.9602316737414047	0.2570479584137060	
+2.3250000000000002	0.0198162574375031	9.8278812395880522	0.0274949664441057	0.0055136869634377	3.0458994210337096	0.1057848538402294	
+2.3260000000000001	0.0701661312622739	9.8308677791059456	0.0126767823719339	-0.0291658367700252	2.9193548435662580	-0.0258780039613425	
+2.3270000000000000	0.0352833381549449	9.8399136577696140	0.0168098188792543	-0.1804707236893253	3.3861462004656784	-0.0841591594495412	
+2.3279999999999998	0.0371587825761032	9.8244156693448392	0.0145153295534101	0.2175653576272296	3.1461385458939777	-0.0190105370240671	
+2.3290000000000002	0.0342456558200327	9.8393396616448747	0.0081896794858103	0.1547944810377488	3.2365628119446210	0.0192468032120728	
+2.3300000000000001	0.0333095075244578	9.8080747874933376	0.0275621899242654	0.2253620737969816	2.9203944444937826	-0.2022246897543880	
+2.3310000000000000	0.0625873202267527	9.8212295361030026	0.0347754888516162	0.3996169799197046	3.2072357742800572	-0.0563457502993403	
+2.3319999999999999	0.0612404736852120	9.8131986060055070	0.0228301624739861	0.1984950548485306	3.0909503284181050	0.1876852351776432	
+2.3330000000000002	0.0407447177141459	9.8344354150505744	0.0404502896735321	-0.0175907821888677	3.2056928986884263	-0.0728793269800295	
+2.3340000000000001	0.0351445404048467	9.8237525591580646	-0.0001810515574385	0.2171104586977644	2.9653007096034636	-0.0254215577591795	
+2.3350000000000000	0.0292111866336509	9.8279862995873568	0.0193678637684817	0.0303004141204265	3.0727469905861922	0.2006374604871033	
+2.3359999999999999	0.0330609463267761	9.8385059461597510	0.0051393033992232	0.2446024167031844	3.2412292815243902	0.0599908851673793	
+2.3370000000000002	0.0257563548111276	9.8164552117057831	0.0239561031798482	0.0849393413946633	2.9189026301512522	-0.0652361681864421	
+2.3380000000000001	0.0336612004316088	9.8063949207532364	0.0198297081898582	0.1680348725561480	2.9944992193686866	0.1748060073601159	
+2.3390000000000000	0.0395102453676878	9.8276134585237980	0.0244505300163885	0.1539256028601309	3.0555480135005522	-0.1459819640660563	
+2.3399999999999999	0.0553774557213050	9.8232407292216024	0.0281335216309653	-0.1654127469381334	2.8889842426886130	-0.1806489824735935	
+2.3410000000000002	0.0105081172967882	9.8261473123167580	0.0189193084248770	-0.2196315213878607	3.0634698170062329	0.2324474381864028	
+2.3420000000000001	0.0428039394012083	9.8289631347871023	0.0022615412431604	0.2846549293632184	2.9336671867613955	0.2866476817122630	
+2.3430000000000000	0.0243908552021599	9.8506213444326480	0.0186068166844640	-0.2019826710744340	3.0222926154743077	0.1444550819155278	
+2.3439999999999999	0.0564171959268680	9.8220363047836070	0.0278484547748246	0.0661900416272795	3.1960123061140200	-0.0050013499224815	
+2.3450000000000002	0.0502234793631279	9.8254945633992232	0.0182995634051531	0.2082149218848811	2.8928893269908302	0.1672149627021009	
+2.3460000000000001	0.0501620793313987	9.8067742572636885	0.0316157007144936	-0.0487066440721383	3.3886492177010687	0.0211362362726298	
+2.3470000000000000	0.0510898763403520	9.8261260935793171	0.0167958255502051	-0.1078824326499284	3.4402528513346740	0.1210527414770539	
+2.3479999999999999	0.0097551742532587	9.8250392643706466	0.0233684430379160	-0.0934285327955104	3.3226658813342578	0.1069014990175153	
+2.3490000000000002	0.0485670055996805	9.8017465156305370	0.0330082965661138	-0.1176868636050080	3.0790409308095250	-0.0429235420025244	
+2.3500000000000001	0.0516580715364038	9.8329028065075228	0.0295656496767544	-0.1625963151714916	3.1899404451942397	0.0164619075330442	
+2.3510000000000000	0.0250796075935480	9.8215158620577068	0.0090759107817501	0.0174487025855353	2.8062401679185034	0.1796370958365105	
+2.3519999999999999	0.0699645903265779	9.8149865052670595	0.0233213337064088	0.0382105377979766	3.2526506771304842	-0.0182575191150347	
+2.3530000000000002	0.0363199646859343	9.8210544172872662	0.0295714004536517	0.2024212988637932	3.1139583442420888	0.2742079901920734	
+2.3540000000000001	0.0169906682091993	9.8247549351079293	0.0243747235448967	0.1923434149569210	3.2552795291566379	0.2056852414600648	
+2.3550000000000000	0.0297024142175725	9.7954979851462056	0.0241405584285748	0.1381564829855715	3.2651063039394836	0.1021986198564373	
+2.3559999999999999	0.0433823564142502	9.8385386967240294	0.0035980554569721	-0.2125454425538810	2.8718698353352656	0.2407209891795046	
+2.3570000000000002	0.0466579341250904	9.8371388906921062	0.0276971232254448	0.0549611978120043	2.9083254618685794	-0.0634821371080227	
+2.3580000000000001	0.0297075144617604	9.8103596832987972	0.0207908156429733	0.3039173128376833	3.2191128838346779	0.1056322331821875	
+2.3590000000000000	0.0443347268822429	9.8093870182868894	0.0214124638816169	0.0632883298271022	3.0606683025560590	0.2476137580549021	
+2.3599999999999999	0.0512737218023207	9.8248930263473664	0.0033976066734487	0.0380408350546261	2.9100304009282505	0.3523634769986994	
+2.3610000000000002	0.0398012825509263	9.8110642205423986	0.0230259132925168	-0.0182122949508092	3.0395632006239803	0.2263537921393541	
+2.3620000000000001	0.0200667770931123	9.8086380982344163	0.0178740014775751	0.0369749592730247	3.1771545056436565	0.1801553043363431	
+2.3630000000000000	0.0417943012288275	9.8375003591265937	0.0145343238989287	0.1676806187362490	2.8607568182119452	0.0164692654560051	
+2.3639999999999999	0.0500643668509973	9.8412542650079029	0.0309263962883478	0.2643031122945078	2.9143391589793475	0.0641823074498577	
+2.3650000000000002	0.0357533951118512	9.8065109093542215	0.0189765291607737	-0.0209860566487743	3.2530377945058087	0.0301024692039596	
+2.3660000000000001	0.0456175535006363	9.8457401252627896	0.0117732164907821	0.0675221066542153	3.0981758033078615	-0.1295504037797168	
+2.3670000000000000	0.0427302020400062	9.8073042931232877	0.0156543751662653	-0.2265546079038546	2.9452427797623724	-0.1353419590003846	
+2.3679999999999999	0.0233869279785561	9.8125154636746323	0.0111277812130846	0.1939430708756904	3.2118569282059841	-0.0895771803830602	
+2.3690000000000002	0.0160011183851733	9.8303490565011042	0.0196743786506626	0.0802726413043824	3.1023089840120659	-0.0663892193472663	
+2.3700000000000001	0.0277265570812646	9.8098411804286574	0.0198254501188916	0.1005962067339634	3.4397906407689307	0.4188917209279018	
+2.3710000000000000	0.0288969362722977	9.8242069083933270	0.0134555198357313	0.1802095765703568	3.0692709952985431	-0.0461854626715716	
+2.3719999999999999	0.0393627000486756	9.8194769207255668	0.0174085825070999	-0.0489976117084501	3.3050658755443454	0.1425890063711016	
+2.3730000000000002	0.0347425974687657	9.8280327224871176	0.0113235358769482	0.1060776862420803	3.0816417087808037	-0.3072007123851319	
+2.3740000000000001	0.0460504239873505	9.8339118584134741	0.0303998628764103	0.0623905105266183	2.8384651788798365	0.3683832753893186	
+2.3750000000000000	0.0483236454260660	9.8328922429960635	0.0104617988513055	-0.0819876193685984	3.3160013749207420	0.1552227881163926	
+2.3759999999999999	0.0200148556180500	9.8226680205881642	0.0136302466677394	0.2695814542611168	2.9489538263067789	0.2844616276454369	
+2.3770000000000002	0.0370075077044649	9.8382717197881338	0.0131224829628133	0.0784304172332493	3.3414748522325732	0.2212592102854795	
+2.3780000000000001	0.0454770052023071	9.8230506547284104	0.0203265702528191	-0.2072357728263003	3.2166313991560136	0.2519693513746241	
+2.3790000000000000	0.0451642452270464	9.8439450150655645	0.0286910197153139	-0.2577182387495994	3.1093283238872398	0.0671208870133553	
+2.3799999999999999	0.0517524759104999	9.8363177738607490	0.0318480393038426	0.2461243926706208	2.9663042314753603	-0.0490281943144608	
+2.3810000000000002	0.0237371868352196	9.8113800205080661	0.0354574675123950	0.0058930166285343	3.0478205064410933	-0.0141930428179138	
+2.3820000000000001	0.0272664594340576	9.8122715438936705	0.0424677274326122	-0.0065657667924041	3.1224696418258060	0.0463489555085403	
+2.3830000000000000	0.0782908958960983	9.8145331427202400	0.0154218754401723	0.1442862154504468	3.1911387699559648	0.0704498807512735	
+2.3839999999999999	0.0404423284549430	9.8406231929844061	0.0167654959949387	-0.0470033299812815	3.3446792273465098	-0.0107371755641539	
+2.3850000000000002	0.0214996957726038	9.8344749395039521	0.0226432808977240	-0.1287045896626375	2.9791915254070322	0.1192790312390374	
+2.3860000000000001	0.0516515017697765	9.8373772138701732	0.0217575339141281	-0.0737514371071970	3.2349564836173301	0.1298083624290992	
+2.3870000000000000	0.0278899109804330	9.8376483021148999	0.0319979771882394	0.0697389646308594	2.9802463189982014	-0.2104625676545979	
+2.3879999999999999	0.0369187357355180	9.8359764832248668	0.0397706618720437	-0.1984116634615665	3.0484004523550521	-0.0479257021405311	
+2.3890000000000002	0.0355627355112497	9.8359388513989430	0.0170138643687036	0.0095922699397158	3.2913970973549387	-0.0449088537434380	
+2.3900000000000001	0.0312584979741593	9.8195650833758634	0.0160261950715885	-0.3001891630447635	3.0131770430015008	0.1993052366110879	
+2.3910000000000000	0.0324175304919911	9.8339409999863356	0.0148591685166504	0.1907083864196397	3.1504240927038913	-0.0141867524905311	
+2.3919999999999999	0.0130422380201434	9.8227687379892714	0.0040507439875072	0.0308495241712175	3.1015606187035321	0.2740804101708443	
+2.3930000000000002	0.0464637201176257	9.8132077294401689	0.0172331700147516	0.0138066980498533	3.0870856246208214	-0.2603744901499568	
+2.3940000000000001	0.0268582948699913	9.8081015004571803	0.0115455578080726	-0.0265841039444495	3.1007257161858246	0.1906514327859878	
+2.3950000000000000	0.0364107779387865	9.8285494098854542	-0.0090553649607179	0.1120101976798675	3.0719786312539958	0.0722026300755746	
+2.3959999999999999	0.0332168582979260	9.8455879041745646	0.0176713136441643	0.0967556495474807	3.1060183550526395	-0.2740354584221343	
+2.3970000000000002	0.0478339399928784	9.8212054418261161	-0.0080951698161915	0.0382778249315431	2.9422975665091640	0.2451692528983219	
+2.3980000000000001	0.0226305570502306	9.8347073454863789	0.0221253461516711	0.2928289403162445	3.0833597986566348	0.2529565794572484	
+2.3990000000000000	0.0449453403882368	9.8244755316686785	-0.0014508887978664	0.1768247304454605	3.2053529071797895	0.1457651071147970	
+2.3999999999999999	0.0311713088651785	9.8222222481102559	0.0446381173007030	0.1755441133715174	3.1648589597969488	0.2207520665576442	
+2.4010000000000002	0.0367199515568536	9.8119957164600731	0.0280626424006890	-0.2178231962383462	3.0337091706877746	-0.0142841433667251	
+2.4020000000000001	0.0233056510483247	9.8115092729167941	0.0096340063854602	-0.1465040937264633	3.0633709636422948	-0.0063300140767969	
+2.4030000000000000	0.0451858855517448	9.8081965166877882	-0.0029365252235271	0.2923851309675502	3.0476030746908145	0.1069419393015555	
+2.4039999999999999	0.0317000268595890	9.8296010417432225	0.0434173903298992	0.1644048378430683	3.0169125855609127	-0.0160460341318461	
+2.4050000000000002	0.0249510017121152	9.8400335420500067	0.0192100266150801	0.0711554068644005	3.2228963375323816	0.0776421354015973	
+2.4060000000000001	0.0325858307143040	9.8433004075788944	0.0345557100789388	0.2356227805721129	2.9527068791090167	0.1623111289264491	
+2.4070000000000000	0.0190787570019576	9.8145306264486383	0.0271021363112364	0.3824189449123819	3.0770043255738520	0.2144423914320513	
+2.4079999999999999	0.0514731500948353	9.8429720357788000	0.0332958718874896	-0.0499397610913358	3.0090212974444399	-0.0217360980623921	
+2.4090000000000003	0.0310620993165746	9.8139479428423630	0.0191686680349352	0.0266771977622688	3.2279701107882275	0.1198577556249064	
+2.4100000000000001	0.0451404420426921	9.8010395349106805	0.0249061835818678	0.2449843261602698	3.0986822092264990	-0.1575233281522425	
+2.4110000000000000	0.0206300178183732	9.8098384169154826	0.0182845689499197	-0.0628593559798076	3.3987282912171000	0.1030277974439433	
+2.4119999999999999	0.0153739158594004	9.8234899616713030	0.0212327467670816	0.2951447067139671	3.3611427676598962	-0.0695435070701457	
+2.4130000000000003	0.0318321758236095	9.8403796906605177	0.0146712991041228	0.0493534801132894	3.0818041195737411	0.1654270763784889	
+2.4140000000000001	0.0219950540371732	9.8221082263520110	0.0166853230302989	0.1264172652292619	3.2901992095891144	0.0032637728794030	
+2.4150000000000000	0.0421093542266597	9.8455416744714395	0.0165359651536193	-0.0768087236662089	3.4989758711407921	-0.0618040306456887	
+2.4159999999999999	0.0315687882227364	9.8395461535935542	0.0128156420095269	-0.0940857190985219	3.2178551443119727	-0.0981330604390631	
+2.4170000000000003	0.0346200429994362	9.8283785529802223	0.0270944075295295	0.1644034497109430	3.1134521447250014	0.2840796969461466	
+2.4180000000000001	0.0255709647907911	9.8185278230210891	0.0111340962061932	0.1069207315835350	3.2309672804911953	0.1403032268905631	
+2.4190000000000000	0.0500771005415626	9.8237738763066531	0.0055754087125691	-0.1649307686426221	2.9927391972984050	0.2961087035541896	
+2.4199999999999999	0.0129420291278663	9.8276768077645915	0.0146468189337454	0.1189457036891739	3.1504855637360607	-0.1241289991002497	
+2.4210000000000003	0.0485220207448880	9.8343241117578089	0.0211711161286792	-0.1876336226687304	3.3616401235292059	-0.0562448218333478	
+2.4220000000000002	0.0402440669428868	9.8283861111887294	-0.0037694778641584	0.0654596839089642	2.8697585046293126	-0.0205186983575800	
+2.4230000000000000	0.0352719174821753	9.8334569045544811	-0.0032297286057241	0.1054795797763655	3.1338803778144873	0.1091625641999108	
+2.4239999999999999	0.0575297614148871	9.8036167931287022	0.0303073630091923	0.1839244070655288	3.1564179717503467	-0.1741689723779273	
+2.4250000000000003	0.0464986025231802	9.8543097581158552	0.0010785749049687	-0.0062725662899406	3.2419205202377417	0.0932558395266430	
+2.4260000000000002	0.0177870124183049	9.8307185709999789	-0.0023463559780514	0.1687991745871265	2.9769452206453888	-0.0097620739236538	
+2.4270000000000000	0.0271111873066615	9.8254731109360041	-0.0021851831270604	0.0216707957000000	2.9023107240729789	0.0479345591145395	
+2.4279999999999999	0.0367766556569555	9.8289109769556084	0.0318708512235666	0.0147940330030075	2.9745532583578473	0.0617947798828950	
+2.4290000000000003	0.0290520666729264	9.8196692722199987	0.0231609013472219	-0.1215164897193375	3.4984603204168891	0.1454944511551771	
+2.4300000000000002	0.0311679838530611	9.8395238710626014	-0.0017968100370358	0.1488041254984371	3.3485139579012406	0.1087018787680893	
+2.4310000000000000	0.0336924228740268	9.8416898313392007	-0.0037839160130947	-0.1314934590711019	3.1666264018446539	0.2081099225666801	
+2.4319999999999999	0.0321917473671614	9.8431496502799298	0.0253110418342443	0.1245797425662352	3.1884226010780869	0.1929403033906695	
+2.4329999999999998	0.0369658889953421	9.8326712332736008	-0.0049501317127469	-0.0236017028744050	3.0932671400071845	-0.0903081236016883	
+2.4340000000000002	0.0229779022572069	9.8189477010164445	0.0272968743304050	0.2864971347654717	3.1522717181850521	0.0580173460619239	
+2.4350000000000001	0.0491275260587881	9.8202022677698260	0.0182082313527919	0.3442397948014785	2.8109583812627790	0.0238469441572448	
+2.4359999999999999	0.0521314349195453	9.8221523425492681	0.0030013488220627	-0.0398149712730356	2.9800919301077649	0.1870759338102507	
+2.4369999999999998	0.0460155950000339	9.8137968319847229	-0.0203219662404940	0.0930281031132105	3.1037029174260589	0.0836657144912138	
+2.4380000000000002	0.0395345387914549	9.8343011284419788	0.0105418417117771	0.1425634556700496	3.0894936065300977	0.1904932159548103	
+2.4390000000000001	0.0513527255045235	9.8422293621286414	0.0049730829636413	-0.0281871441000792	3.0831956004506846	0.0090935842782561	
+2.4399999999999999	0.0308813779748824	9.8227207857228809	-0.0060118059408398	-0.0148470289857613	2.8676418722447257	0.2053090926503915	
+2.4409999999999998	0.0298675570084037	9.8178300721933027	0.0387833777805267	0.0020660937450137	3.0411142722002271	0.0658141422481686	
+2.4420000000000002	0.0235941014571023	9.8186360777698685	0.0032545880245214	0.2678602876794182	2.8497739995558731	0.1770469482943939	
+2.4430000000000001	0.0285409990862889	9.8150149295174973	0.0146875661161025	-0.1239161619019863	3.3189395440035740	0.1360597384394630	
+2.4440000000000000	0.0369471606148835	9.8446378011502347	0.0195708637746007	0.0218035316718965	2.9275447512124737	-0.0488532114119190	
+2.4449999999999998	0.0405412777731362	9.8170045970979611	0.0285967656943759	-0.0021390591221964	3.0004615472284790	0.2030446728138100	
+2.4460000000000002	0.0390814942120886	9.8201736312290855	0.0156272625602832	-0.0969293822369971	3.3285427612392642	0.0723356340353083	
+2.4470000000000001	0.0215203527483134	9.8233899503559687	0.0084878291346619	0.0193750141730562	3.3996500941986749	-0.0349315441329484	
+2.4480000000000000	0.0390542931768441	9.8034461840229916	0.0343493034814492	0.1277026629845029	3.3862573691687818	0.1139528469447889	
+2.4489999999999998	0.0440767121061483	9.8337281915242443	0.0142963362376846	-0.0101656863972752	3.1862240293267261	0.1538396119037570	
+2.4500000000000002	0.0204967491551565	9.8094554301780423	0.0153184675502403	-0.0663683442546574	3.0901898254369495	0.2891396759384947	
+2.4510000000000001	0.0252768223668233	9.8118179460413675	0.0007036279075156	0.2547861305888761	2.9377432866243209	-0.1959037488348506	
+2.4520000000000000	0.0421218186131953	9.8137326459204015	-0.0005863519186316	0.0229384050079501	2.9917821144332644	0.1689193161683551	
+2.4529999999999998	0.0257379500850011	9.8229154956838691	0.0043373455548931	0.1755849047480201	3.0819595336285861	0.0376063264136659	
+2.4540000000000002	0.0167199111147937	9.8372967552402066	0.0234586120788166	0.0677442584983912	3.0933433783248501	0.1285947115630861	
+2.4550000000000001	0.0331141059391411	9.8328414886499029	0.0297331122182762	0.0940387548593812	3.4299627099064365	0.2540998563552962	
+2.4560000000000000	0.0339776478249501	9.8258134928731362	0.0163831370465623	0.0210914238407630	3.0907976009431084	-0.2544672683482206	
+2.4569999999999999	0.0662115829227936	9.8193596827304894	0.0148210878819718	-0.0442746287296625	3.0569287546914294	0.4709544065837284	
+2.4580000000000002	0.0409454716487904	9.8301422884223690	0.0388157307253470	0.3000308829630347	3.0277948240124739	-0.0491377470859387	
+2.4590000000000001	0.0393539000568219	9.8488242380009368	0.0035085320090978	-0.0729826464506457	3.3307725446760150	0.0490701675660635	
+2.4600000000000000	0.0394614901373299	9.8102329388883494	-0.0093740678509074	-0.0958009882055938	2.8914979472493370	0.2523796090571907	
+2.4609999999999999	0.0514399714803737	9.8334815586920055	0.0235757010309462	0.0991526394821341	3.3116558733876889	0.0740712493166716	
+2.4620000000000002	0.0476915672673881	9.8351992373325654	-0.0054613373158540	-0.0085818033656400	3.2032049155484281	-0.2729894877769390	
+2.4630000000000001	0.0329915609118647	9.8191069739741064	0.0046533252355103	-0.0167404041660586	3.0135410656543913	0.1330152143688041	
+2.4640000000000000	0.0421986940934846	9.8529771509778961	0.0105505361274458	0.2316507025820221	3.1992035111103099	0.1080385743659720	
+2.4649999999999999	0.0679448651226256	9.8382996555042457	0.0290895528060541	0.3194423497803294	2.9467795558304877	0.1817100923363853	
+2.4660000000000002	0.0350094714624562	9.8044084725319820	0.0192866183132330	0.0376931482571275	3.2404902272800342	0.2906368448156442	
+2.4670000000000001	0.0462977049481034	9.8189829728777731	-0.0237301893835675	0.0540407007257177	3.1894541072641789	0.0286233615097555	
+2.4680000000000000	0.0212751384158249	9.8360519138408318	0.0008227201143774	-0.0029677895135369	3.0666169887836285	0.2172182229091634	
+2.4689999999999999	0.0436012804924315	9.8378855006359096	0.0152232071947772	-0.0475878156526729	3.0872356502753009	0.2410311759546722	
+2.4700000000000002	0.0236615108091008	9.8268609758238394	0.0114428882309994	0.4502671270503030	3.1374103978533352	0.2029022311984123	
+2.4710000000000001	0.0417901724508466	9.8228856719954027	0.0002846180464767	0.1586045012640313	2.9668597268513923	0.1538924328012493	
+2.4720000000000000	0.0243339151246065	9.8429766390289171	0.0075372319877676	0.1226488773344709	3.1745828552568236	0.1621377931057655	
+2.4729999999999999	0.0415135462300368	9.8175648107403362	0.0031271372702828	0.0953328834381029	2.9694021152158312	0.2654829509729495	
+2.4740000000000002	0.0495745831289181	9.8203316527127011	0.0014340260967293	-0.0080716219298174	3.0165528100281813	0.0848288054873620	
+2.4750000000000001	0.0178604098255117	9.8204667608610858	-0.0175185928272872	-0.0362766119694600	3.1139903956478636	-0.0301275505479767	
+2.4760000000000000	0.0340800925544771	9.8404304036394521	-0.0043443058716477	-0.4027017957277541	3.1538307984367604	0.0217968224334095	
+2.4769999999999999	0.0549802844828909	9.8446859925637789	0.0208443088550938	-0.0038118892990680	3.0034612229399666	0.0329672423322638	
+2.4780000000000002	0.0187405348599412	9.8320178132938167	-0.0072073584350513	-0.0248053924944378	3.1726758585166577	0.1836817874070928	
+2.4790000000000001	0.0298235645035261	9.8274305364485457	-0.0034267237274879	-0.0115985496585966	2.8646224716688495	0.0937875380758538	
+2.4800000000000000	0.0435728890517153	9.8126198406610001	0.0253864074673974	0.0531826879580427	2.9359856939485076	0.1681418271089854	
+2.4809999999999999	0.0498908262518162	9.8496853095631582	-0.0079334518346045	-0.1981837675488060	3.0991291952829441	0.0529927515500757	
+2.4820000000000002	0.0230288928464336	9.8227175089733212	0.0066179142075734	0.0144435202153229	3.3117654113144841	-0.0391773067451606	
+2.4830000000000001	0.0110215607861995	9.8157198856775025	0.0017180878182493	0.0816820052166585	3.3716440396812364	0.1255003712652059	
+2.4840000000000000	0.0235635056380308	9.8265322184415567	0.0152985151436873	0.0777314029993077	3.1137025950444217	0.0066832056132099	
+2.4849999999999999	0.0325038087709184	9.8109405524211724	-0.0099307133039824	-0.0489142383843623	3.0477685854198584	-0.2717637027245032	
+2.4860000000000002	0.0232218315433486	9.8337213381482460	0.0103162613605362	-0.1249300460074567	3.2143100481426270	-0.1220717891847872	
+2.4870000000000001	0.0205208205080336	9.8377533957666259	0.0234055536991811	0.3534153391693886	3.3444831011772735	-0.0799950395936880	
+2.4880000000000000	0.0469293168182217	9.8299659515559270	0.0198773283425606	0.0643616743155462	2.9216045762686944	-0.1358304411676763	
+2.4889999999999999	0.0463047833004332	9.8164185333925875	0.0091625023765225	0.2066312062272999	3.2226888321268898	-0.1558145449943560	
+2.4900000000000002	0.0205433610070325	9.8343273613393105	0.0181857848223358	-0.0537843592377168	2.8142939712140844	0.1777946683023156	
+2.4910000000000001	0.0151126927442719	9.8349123531392824	0.0261428202433025	-0.0626291634360267	3.1752554861165723	-0.1140215730938551	
+2.4920000000000000	0.0306031517339961	9.8284096820201086	0.0239583720692110	0.2308301664439302	3.2217181701842250	-0.1298463004013016	
+2.4929999999999999	0.0086764162760703	9.8406598272358927	-0.0055413971786537	0.0896028604828549	3.2163352465420791	0.2296148057326760	
+2.4940000000000002	0.0460221897272314	9.8122099939068299	0.0073448798683826	0.0145794233839067	3.3478115112169351	-0.0672296620574296	
+2.4950000000000001	0.0078775090941392	9.8376321665312378	0.0151668593799813	-0.0735045735867056	3.2609439165919922	0.1701917935492846	
+2.4960000000000000	0.0512642011604791	9.8359426487600139	0.0069273510352954	0.1028881580953717	3.1649353806917571	0.0668905933315497	
+2.4969999999999999	0.0498925787148446	9.8395229408432421	-0.0145376218533685	0.0057370466049490	2.9833283692278236	0.0595853717998652	
+2.4980000000000002	0.0218263728794450	9.8494466014660276	0.0131639811168505	-0.0828336766407764	3.2078119460360965	0.0327991929939735	
+2.4990000000000001	0.0527550052320750	9.8391179620643427	-0.0124340725211950	0.1551385903111441	3.2315455182791180	0.1087511548291734	
+2.5000000000000000	0.0159955610077298	9.8275058867088578	0.0271021394110960	-0.0008061476386286	2.8542969709693278	0.0834399163369814	
+2.5009999999999999	0.0276922030904914	9.8150002210263434	-0.0070072000968347	-0.0337506420183287	0.1235366217166592	0.0282662433228494	
+2.5020000000000002	0.0412627785389649	9.8229375299214094	0.0013442436727589	0.1858076414481776	-0.0817901512946173	0.3160172945667972	
+2.5030000000000001	0.0366751683971110	9.8366638829507078	-0.0216214761652394	0.1278552547616361	-0.0400381338016563	0.2081394998588506	
+2.5040000000000000	0.0321597332941806	9.8321152974781363	0.0048139037733235	0.2119976241379129	-0.0264936893758090	0.1451464334557249	
+2.5049999999999999	0.0161500830022471	9.8328284404136586	0.0123742350919298	-0.0569020576905486	-0.1298517455489435	-0.1077495743070468	
+2.5060000000000002	0.0461885821908255	9.8334678172034629	-0.0138980015651583	-0.0663022261979271	-0.1835713651267775	0.1084731630153765	
+2.5070000000000001	0.0112988931888684	9.8234623082802202	0.0055256726359539	0.2622660205679839	0.0437549782037799	-0.0679888196544511	
+2.5080000000000000	0.0390672719268535	9.8452158084113677	0.0157795871400270	0.3236655937928000	-0.0285352046611339	-0.0047839012357473	
+2.5089999999999999	0.0550324517692692	9.8271998119114574	0.0107343295434630	-0.0224284874193062	-0.0585060996816103	0.1248576011338995	
+2.5100000000000002	0.0349968820388455	9.8467715944535339	-0.0078136822674401	0.0848467196768071	-0.2592822372152512	0.3137479919546125	
+2.5110000000000001	0.0385460574770810	9.8443962483389864	0.0127362455637776	0.1690392549512101	0.0406081623152566	-0.0107257582164939	
+2.5120000000000000	0.0585151640210914	9.8443091077068186	-0.0004662379667076	0.1171629772023852	0.0244013740992109	0.1452260667859177	
+2.5129999999999999	0.0361473948212498	9.8242366639667882	-0.0018601991686820	0.1442597632831328	0.0599262578683439	0.4092263200579732	
+2.5140000000000002	0.0219640688305363	9.8224139703855293	0.0195208422703875	-0.2151989135526580	-0.2117046248303391	0.2123087492622533	
+2.5150000000000001	0.0312995820351005	9.7981963338767031	0.0043754946682174	-0.1698611973738407	0.1164238520808250	0.2737851608714104	
+2.5160000000000000	0.0645756687204576	9.8445234315015568	-0.0085603091142175	0.0902356689535447	-0.2612782090888684	-0.0935619088129443	
+2.5169999999999999	0.0273561115695171	9.8240820618030718	0.0125475641068083	0.0312922989594176	0.0085875820413249	-0.1091004061296503	
+2.5180000000000002	0.0480228283690081	9.8062913808054351	0.0070846773333937	-0.0275819606803096	-0.0359531802712548	0.0445981647041306	
+2.5190000000000001	0.0357726828648981	9.8309833810035148	-0.0253952271559808	0.0582363072876336	0.0102099031082396	-0.1095801511720943	
+2.5200000000000000	0.0383056510775977	9.8354894676270899	0.0075258552266573	0.1158524163768791	0.0065658679973339	0.0209086409902278	
+2.5209999999999999	0.0312152524267042	9.8324191856231486	-0.0307678310600083	0.1771728641221335	-0.0273990969348451	0.0205343729448559	
+2.5220000000000002	0.0356791385049645	9.8319191517776670	0.0033131326835918	0.2493329128450278	-0.2314383224872983	0.1030814905431811	
+2.5230000000000001	0.0365783711800065	9.8247561284692022	-0.0041465855620046	-0.2599344689061767	0.0602804224185044	0.0807605937318878	
+2.5240000000000000	0.0125892099000062	9.8377078828995383	0.0083513797566430	0.0742718816021724	0.0030234569486816	-0.2368528420092662	
+2.5249999999999999	0.0269509789996882	9.8325330039630767	0.0076421850745222	-0.0738577127300034	0.2853997116339880	-0.1342022899321966	
+2.5260000000000002	0.0429793708605321	9.8448520477710719	0.0009628200853266	-0.1256773247589343	-0.0714670358852783	0.0988094071377050	
+2.5270000000000001	0.0399995633292002	9.8138385793372791	-0.0039728660445928	0.0100409324685610	0.0708770698272540	0.1358388271351244	
+2.5280000000000000	0.0667735754652304	9.8302152657179978	0.0200185933858294	0.2369901019684946	0.0087645362467598	-0.0799232930546668	
+2.5289999999999999	0.0547526612250820	9.8228337007947886	0.0081335965493286	0.0455940512060750	-0.1260640034039604	0.1028196834947611	
+2.5300000000000002	0.0446517927970684	9.8280016709465503	0.0134850514464041	-0.0768506788944385	-0.1252289701938364	0.4629283070185002	
+2.5310000000000001	0.0191317220701759	9.8439075643689335	-0.0066244938912364	-0.1776432605598573	-0.4653033652243319	0.2482355837056162	
+2.5320000000000000	0.0319467070152613	9.8251189117014732	0.0106900912705148	0.1790612080521947	-0.0139964082589872	0.0672965796835999	
+2.5329999999999999	0.0157380251489685	9.8115408591175672	-0.0012448775144810	-0.1487627561645585	-0.0948654699355444	-0.4475798896397676	
+2.5340000000000003	0.0207182521167093	9.8165699809176861	0.0146998641438814	-0.0318160275016892	-0.1079730482960735	-0.0214338480377602	
+2.5350000000000001	0.0592351513945496	9.8170657123780138	-0.0216676259256287	0.0408902135479700	0.1251704358685953	0.0383152719961527	
+2.5360000000000000	0.0623113054624149	9.8103173756730992	0.0182261521567864	0.1847982985291226	0.1020899464570438	0.2482490656350889	
+2.5369999999999999	0.0381290397704324	9.8181361046996916	0.0123588931216051	-0.0129427352796295	-0.1310888861071546	0.2877943865425926	
+2.5380000000000003	0.0433473130928467	9.8267136435394047	0.0163995792267995	-0.0011129835165896	-0.0359466867552793	-0.0651736668544550	
+2.5390000000000001	0.0547016555428822	9.8134839252450465	0.0059224937394937	0.2041253949338950	-0.0183511226036571	0.2065506916459234	
+2.5400000000000000	0.0497267594174953	9.8455805899473230	0.0088289681122446	0.1613007250867602	-0.2395574072892021	0.1767467405410301	
+2.5409999999999999	0.0223402126509817	9.8221694480338400	0.0163109018841708	-0.1884301351542813	-0.1240380397025242	-0.0752484542771127	
+2.5420000000000003	0.0408971326844418	9.8309673467027263	0.0125816761887441	0.1214220203282177	0.0534245845993389	-0.0058373578810929	
+2.5430000000000001	0.0556173399865669	9.8396084259686045	0.0065723456212096	-0.0404606193467667	-0.0818826342181928	-0.0602935077293123	
+2.5440000000000000	0.0181701886367809	9.8266454649419117	-0.0111326334311001	0.0539726325712987	0.1967295428719411	0.1075640010080938	
+2.5449999999999999	0.0371280638449751	9.8265111329654129	0.0068423876684022	0.2062207967580160	-0.0259036539128678	0.0812597712489278	
+2.5460000000000003	0.0250736949718350	9.8121232847889797	0.0092904997973800	0.0656487902527363	-0.0205246416497943	0.0256080006045748	
+2.5470000000000002	0.0386933645446679	9.8362206998237838	0.0059146417010290	0.1335459910822184	0.0339561181748493	0.0884477277995795	
+2.5480000000000000	0.0527332875654047	9.8324767918172693	0.0101038377351735	0.0473993241752330	0.0294377769120830	0.0840988555146353	
+2.5489999999999999	0.0456148985864035	9.8223926663357641	0.0012891613471216	0.0607187547334864	-0.2940152325895171	0.0138498471632445	
+2.5500000000000003	0.0259435928125108	9.8100374230581018	0.0149681010479894	-0.1475712605579813	-0.1723578767458607	0.1044488471346898	
+2.5510000000000002	0.0446080156633555	9.8057855722242913	-0.0077192461362926	0.1564201889405470	0.0467287671551499	0.2539949408170182	
+2.5520000000000000	0.0316036865668997	9.8278228516468964	0.0158910782615633	0.3318029140117706	0.1381309177199060	0.2781503893656140	
+2.5529999999999999	0.0281014268001753	9.8247442618446499	0.0084789059062362	0.2568113467319582	-0.1380335972003757	0.1031655328801470	
+2.5540000000000003	0.0236395284588786	9.8285480781540109	-0.0181451553851056	-0.1364425064214347	0.0162815267614269	-0.0647285873071059	
+2.5550000000000002	0.0274033276536194	9.8059575339439018	-0.0052878165575171	-0.0792989314423544	-0.2198972809905605	0.0021153469985751	
+2.5560000000000000	0.0417522654784727	9.8141696128597431	0.0116242485143525	0.1518643577203854	0.2091694749817224	0.3191917658158551	
+2.5569999999999999	0.0317674063116850	9.8388918823334031	0.0027459886555036	0.1154377453866601	-0.0245722683244599	0.3271058624768558	
+2.5580000000000003	0.0288207394582644	9.8394656071986031	-0.0003339819765580	-0.1753491960600520	-0.0678856002596494	0.1758047431784382	
+2.5590000000000002	0.0311895237130569	9.8084955441102046	-0.0195319107423582	-0.0423460919939097	-0.0936080966484152	-0.2110791376992957	
+2.5600000000000001	0.0366228489407868	9.8245103918097509	0.0100322917207303	0.0417254879940266	-0.2393869758690872	0.2935679699511117	
+2.5609999999999999	0.0471472203593358	9.8157365197941253	0.0132674696829903	0.0190649228467619	-0.0957056285595368	0.2209446795921799	
+2.5619999999999998	0.0460551090285043	9.8298681310105280	0.0024119154295146	-0.2288094655483258	-0.0914302359200405	-0.0024280372638159	
+2.5630000000000002	0.0364923693104534	9.8261559255242368	-0.0059330107543655	0.0149872009770522	-0.0895056009051224	-0.0113131746053227	
+2.5640000000000001	0.0148830330066438	9.8242789427838062	0.0029626350012484	0.3816496065780277	0.1569130847313658	0.2435272945200912	
+2.5649999999999999	0.0431440195106895	9.8157280949897761	0.0009634673851448	-0.0444577701097321	-0.1431164579723861	0.3706643145099420	
+2.5659999999999998	0.0702064877827031	9.8066873348164165	0.0147297673061458	0.0264309881331011	0.1157738714912422	0.0444549917859717	
+2.5670000000000002	0.0201692450238568	9.8335248456972835	-0.0013464771743034	0.1071742426829511	0.1190945422723079	0.0610621468256621	
+2.5680000000000001	0.0232730756987195	9.8090781271988199	0.0098714834029282	0.2025561819703129	-0.0065717137735574	0.1229863087533829	
+2.5690000000000000	0.0328947167080225	9.8182671774152439	0.0139671091575021	-0.1992365910169386	-0.2371503427177004	-0.0161549390278817	
+2.5699999999999998	0.0178130443276146	9.8261434111632724	-0.0064305152682014	-0.1610782985658173	0.1687743805523887	0.1112660509561975	
+2.5710000000000002	0.0336577503612389	9.8494537888623164	0.0279275306350376	0.2146367410441111	-0.0050396923258617	0.1492793684285798	
+2.5720000000000001	0.0524805681838490	9.8201605141306398	-0.0023731207699498	0.0815337793563251	-0.0694503053714401	0.1160525397406910	
+2.5730000000000000	0.0271360157034940	9.8032937947385044	-0.0166676627649458	0.2883650175525442	-0.2067379788947922	0.4773051364868170	
+2.5739999999999998	0.0383240355726720	9.8388084806181428	-0.0004773752468647	-0.0041108718304760	0.2115420650067312	0.0841634733464582	
+2.5750000000000002	0.0651180614630024	9.8317717759949943	0.0216251047104885	-0.1239802653602719	0.1003113290309489	-0.0786811295805286	
+2.5760000000000001	0.0309137016422477	9.8466717867333582	0.0045055363715624	-0.0210364179301781	-0.0080041057671278	0.3816924471082364	
+2.5770000000000000	0.0286239799877468	9.8418766526480148	0.0022653748690630	0.1447619519126799	0.0133213430126529	0.2758795330709464	
+2.5779999999999998	0.0361889456742114	9.8252867309747369	0.0228343938041776	-0.1062102654163491	0.0288187350470168	0.2022702568595911	
+2.5790000000000002	0.0413647388994436	9.8180124319205841	-0.0150773146284295	0.0808268798009417	-0.0173591405072160	-0.0742924300352732	
+2.5800000000000001	0.0421711199972364	9.8230421139412520	0.0133168861424595	-0.1565371916219738	-0.0889460059944407	0.2261039289487948	
+2.5810000000000000	0.0342214153924691	9.8220885164609211	0.0085758282119074	-0.2211739497621356	-0.2307509663273536	-0.2000771199170268	
+2.5819999999999999	0.0449529300429156	9.8272302865799386	0.0194330825449052	-0.0291632803246399	-0.1264762406834477	0.1162463381887329	
+2.5830000000000002	0.0305457894598135	9.8292645441525810	0.0092508889969769	0.1346919376355937	0.0956293901175990	0.3111616606959729	
+2.5840000000000001	0.0109666167155572	9.8442007739545812	0.0041081324204829	0.0868977881895498	0.0787692158433537	0.2358111837438481	
+2.5850000000000000	0.0352994316811010	9.8167787208156767	0.0199473511030584	-0.0511215745911639	-0.1528133043613794	0.0020909500519341	
+2.5859999999999999	0.0177562515341459	9.8257160367565586	0.0238286825564179	-0.0101547121244055	-0.2740372282682255	0.0312313066015643	
+2.5870000000000002	0.0328647807779930	9.8060983286662804	0.0105314369389042	0.0454784075887666	-0.1012034820864346	0.3008205977230996	
+2.5880000000000001	0.0283461692559303	9.8247570106973203	0.0153409486055061	0.0220426228300119	-0.2189696563316851	0.1782757472426181	
+2.5890000000000000	0.0544486993076246	9.8322151947103080	0.0229618936249645	-0.0961932644465645	-0.1092722181980534	0.1425287082268780	
+2.5899999999999999	0.0584734615888946	9.8287932385092063	-0.0177315980680626	0.0442668222583633	-0.1628871222806365	0.0377197636886201	
+2.5910000000000002	0.0455397628403432	9.8613594831761322	0.0191584909667708	0.1440159923184325	-0.0753425308918364	0.1414957659335490	
+2.5920000000000001	0.0473942037070164	9.8475628650216507	-0.0120552319494630	0.1320394852109065	-0.1645978142397203	0.0764503108476563	
+2.5930000000000000	0.0264840996455834	9.8258652547204282	0.0090135234953079	0.1436126074428395	-0.0703490940687312	0.0303129194076562	
+2.5939999999999999	0.0272967140776665	9.8216729875306719	0.0122500526681807	-0.1174964113204041	-0.0281239157687362	0.1175414274032167	
+2.5950000000000002	0.0371366781053151	9.8097688013280759	-0.0011213259682962	-0.2038503446170108	0.0807862914390828	0.2242818119810934	
+2.5960000000000001	0.0320657241419335	9.8302232632547621	-0.0026551741552724	0.0978158501386731	-0.0892647623565704	0.1864818157086831	
+2.5970000000000000	0.0266416727743195	9.8121349706738599	0.0209740058284857	-0.0276478638895170	0.0282012821241830	0.0011129602175637	
+2.5979999999999999	0.0327748911775750	9.8508135886415005	0.0090097460068281	0.2586211703869564	0.1349196725824318	0.0559171080308414	
+2.5990000000000002	0.0404313220854605	9.8245090083727860	0.0011590812038295	0.0556437744680584	0.0184140922073484	0.3187147074663053	
+2.6000000000000001	0.0277070983194650	9.8063229375399601	0.0194716345695801	0.0990930622736564	-0.0994690540123916	0.3067629844531131	
+2.6010000000000000	0.0564685528594629	9.8472308278139504	0.0225929871616794	0.0619256681608250	0.0136234874958772	0.0505977187229662	
+2.6019999999999999	0.0289590418135758	9.8389979995005419	0.0072666661636658	-0.0547999161445830	0.0578363799621741	0.3143273101683217	
+2.6030000000000002	0.0195972063315052	9.8165309165956494	0.0048129068456919	-0.0938050614603957	-0.1531305954860301	-0.0058943945235577	
+2.6040000000000001	0.0368231849005435	9.8261225291750840	0.0002293522282912	-0.0608715991652813	-0.0716264985118025	0.0306178079717967	
+2.6050000000000000	0.0370069638599996	9.8159606918999796	0.0012442299684651	-0.0423862817120896	0.2449296802783830	-0.0073949917913272	
+2.6059999999999999	0.0389972841034958	9.8219332623572146	0.0139223486009523	0.0465924678988161	0.0361404741699406	0.3487276347158042	
+2.6070000000000002	0.0427217324887632	9.8007813679495843	0.0092371808814980	0.0846733529269555	-0.2121212002757609	0.1257346842473127	
+2.6080000000000001	0.0202505059739802	9.8257269881882401	0.0018455713319584	0.0001683798113590	-0.0071057508110377	-0.0322099672534037	
+2.6090000000000000	0.0300210496764720	9.8217659553854180	0.0102826577976053	-0.1562866641908507	0.0480789557248652	0.0607928703098153	
+2.6099999999999999	0.0234242287481194	9.8182536135183565	0.0116468768073653	-0.0371348079687088	0.1389490566551739	0.1151115354326400	
+2.6110000000000002	0.0190314300543287	9.8559164340372316	0.0291987150792101	0.3635594836486516	-0.0361400694212725	0.1653890568415459	
+2.6120000000000001	0.0505877665983409	9.8451207212521208	0.0168805624326023	-0.0508948815054973	0.0569456828414672	0.1787859717936811	
+2.6130000000000000	0.0280444441621377	9.8173720172676955	0.0039705098406024	0.1499105460033164	0.0969853199049875	0.1594007415724820	
+2.6139999999999999	0.0259782228186756	9.8172977919999092	0.0145611022940156	0.2412422476812850	-0.1689280309916917	0.1389860056642516	
+2.6150000000000002	0.0299086150710371	9.8283323384378019	-0.0149838419724198	0.2198840911513228	-0.1655178159253541	-0.1846430945778479	
+2.6160000000000001	0.0216483456525588	9.8324537626448656	0.0081358768416201	0.1249427093589240	0.2889733491457430	0.1028914827732714	
+2.6170000000000000	0.0396279745576490	9.8184954121008534	0.0027328664200131	-0.1793474105843474	-0.0017240559420842	0.1545876859660972	
+2.6179999999999999	0.0416170807290759	9.8115884134344284	0.0127911203269683	0.0110582355751058	-0.0849571535579979	-0.0991818817152009	
+2.6190000000000002	0.0209905959811106	9.8350248949142571	-0.0056582437626559	0.2623398829020350	-0.1300686061389147	0.1571502713877366	
+2.6200000000000001	0.0568487354492325	9.8233781680952763	-0.0099888775209778	-0.2404597439958939	0.2826073726584359	0.0615489623079851	
+2.6210000000000000	0.0351557085962350	9.8180071998078979	0.0041007429709243	-0.0058151502047042	-0.2491160600947160	0.1337379406503496	
+2.6219999999999999	0.0267847949487396	9.8393272771069942	0.0063721573985646	-0.0748774776633628	-0.1873675466063109	0.1773381620675628	
+2.6230000000000002	0.0121769934854122	9.8247711973444645	0.0057695823394200	-0.0071800292077117	0.0984971177410099	0.3219390103890234	
+2.6240000000000001	0.0345698899509153	9.8212496260007267	-0.0109772722387868	0.1099328309507332	0.1238989397375045	0.1088266703927713	
+2.6250000000000000	0.0325926836225966	9.8430409789667141	0.0182409651437233	-0.2595048839721423	-0.0092061060527458	0.1068460530921652	
+2.6259999999999999	0.0495711432730999	9.8273165847597106	-0.0070225651463702	0.1509039412964870	0.2991097363047311	-0.1934176622548994	
+2.6270000000000002	0.0396194290443767	9.8206632736051027	-0.0217439209390906	0.0858570252620713	0.1879615866494000	-0.0576424572358784	
+2.6280000000000001	0.0150783466462585	9.8299429883257741	0.0022694105241643	-0.0880628791585107	0.1376895029687898	-0.1538872977401174	
+2.6290000000000000	0.0273071826963795	9.8305717637531238	0.0123605513619109	-0.0476312899679309	0.1318817440919741	0.1617453399195962	
+2.6299999999999999	0.0399581925812100	9.8326146144763342	0.0186362435687235	0.1314616223142828	-0.3427509740625809	0.2324171016338239	
+2.6310000000000002	0.0125977666194992	9.8270167697965949	0.0003355988945151	0.2413477018337914	0.2404082610501583	-0.0606078529324002	
+2.6320000000000001	0.0429079809439055	9.8447978745256624	0.0068888210047153	0.2359641411167349	0.1441297237830315	0.0802598857610191	
+2.6330000000000000	0.0379460273991750	9.8123517159024178	-0.0007814596129721	0.0808105105603800	0.0969081516770324	0.3388655563626704	
+2.6339999999999999	0.0430769609995417	9.8217427476410695	0.0027845264838403	0.0774054010717673	-0.2204986067727771	0.2111571901640296	
+2.6350000000000002	0.0574450838176871	9.8464929214869787	0.0100214384997384	0.0365961374757686	0.0387018280033539	0.2028493772194239	
+2.6360000000000001	0.0396618700179018	9.8095532667445049	-0.0071860553128584	0.1159865043064422	-0.1352311708482216	0.0053174514719725	
+2.6370000000000000	0.0266256025274814	9.8413775373545693	0.0096801627092173	-0.1733102589948968	0.2034671562264402	-0.0943289521933215	
+2.6379999999999999	0.0324930216170184	9.8492103260472224	0.0089830265663570	0.2082480069119669	0.1426561522196804	0.1633575996280356	
+2.6390000000000002	0.0206589198380987	9.8220575699110988	0.0010715866676672	0.0094716987439399	0.0744973986055671	0.0593034736798699	
+2.6400000000000001	0.0398370174373255	9.8420569190259641	0.0044776057556906	0.2595221158375968	0.0956862172907407	-0.0264129591821262	
+2.6410000000000000	0.0379388261574482	9.8352393655001791	0.0221256564084787	-0.0012427428086210	0.3883261625958580	0.0409813810897835	
+2.6419999999999999	0.0327821737341267	9.8248395292799184	0.0174351520289537	-0.2070632419813158	-0.1880383568259429	0.2965851685606287	
+2.6430000000000002	0.0386867823668032	9.8346273484454478	0.0153764841956687	0.1247455971377320	-0.0670631626962053	-0.2967966407093933	
+2.6440000000000001	0.0212412339922740	9.8249896149006375	0.0114811770573285	-0.1827494623940752	-0.1545361072894464	0.3596421007693046	
+2.6450000000000000	0.0265616246130942	9.8602028501407784	0.0174159468761049	-0.0927050779789755	-0.1472259057006027	-0.0283560558820095	
+2.6459999999999999	0.0249860505770063	9.8367169856121599	0.0134122654131607	0.0892987828804915	0.1948258078185130	-0.0263625790135582	
+2.6470000000000002	0.0414844085318707	9.8187045753039257	0.0008263905097590	0.0980590564504969	-0.0445420368748566	0.2304374115033823	
+2.6480000000000001	0.0274595809952701	9.8235947276670093	0.0233822103361515	0.2738459937514313	-0.0117979937914418	0.0896145351527860	
+2.6490000000000000	0.0280228513680775	9.8167780789630577	0.0179045451545830	-0.0539714234593795	-0.1484487516378256	0.3376223886837860	
+2.6499999999999999	0.0264146500539512	9.8333663863548484	-0.0036112952764886	0.1694019546381053	0.1758956776715614	-0.0043354918315379	
+2.6510000000000002	0.0222830630365994	9.8248924882344717	-0.0013234562349411	0.0056895103694182	0.2281069188296451	0.0906585285428097	
+2.6520000000000001	0.0174620048720630	9.8214091881762489	-0.0034226452863948	-0.1477996230223825	0.2198983137836460	0.2059592831538096	
+2.6530000000000000	0.0293991778469587	9.8237040694386835	0.0187839029792935	0.1511987441030767	-0.1328751241312513	-0.1895732148409634	
+2.6539999999999999	0.0320803107382196	9.8387883952289208	0.0178883551916110	-0.1109307884214745	-0.0507380005384104	0.1030955655598299	
+2.6550000000000002	0.0364601760518178	9.8173616145584166	0.0245227462660945	0.1381191249935387	-0.0290395552059040	0.1537888931268656	
+2.6560000000000001	0.0484408202126741	9.8257065157633967	0.0023901225526286	-0.0310099182083747	0.2176301839331211	0.2430517957979882	
+2.6570000000000000	0.0260381925019728	9.8213816216667666	0.0015878884858208	0.0511715729756416	-0.0051352197081310	0.2227143542433767	
+2.6579999999999999	0.0261914891159385	9.8515855876863174	-0.0028722577384764	0.0033614944803347	0.2897600555903061	-0.1273913506604588	
+2.6590000000000003	0.0337471152510624	9.8185988318201431	0.0103454253779069	-0.0990936395833928	0.0062048659493975	0.0970837052908987	
+2.6600000000000001	0.0393827857220625	9.8156088552897796	0.0069286644475902	-0.2569002400599478	0.3175304164837168	0.1256477903880210	
+2.6610000000000000	0.0347564606309244	9.8178690883670168	0.0330531052188019	-0.0775253984115330	-0.0134425915531041	0.0281124682158314	
+2.6619999999999999	0.0348981031423159	9.8440118984409306	0.0330925289602535	0.3867527615380903	-0.1098608722379251	0.2050183966378749	
+2.6630000000000003	0.0457822141276074	9.8157094155456512	0.0115378415503527	0.1999354814536687	-0.2912440059630183	0.1818229677144684	
+2.6640000000000001	0.0329960860856026	9.8281790455216385	-0.0118707149024244	0.2529309320289864	-0.0085615458544596	0.2131109770728061	
+2.6650000000000000	0.0414939187021980	9.8039853514976691	0.0071882931736906	-0.0888908274837322	0.1057576807379080	0.1624052556322867	
+2.6659999999999999	0.0379915993801047	9.8239560472181555	-0.0012030564795335	0.1941720751134228	-0.1012144961137585	0.1360479282741273	
+2.6670000000000003	0.0323695191907320	9.8132205395197047	0.0256231825545890	0.0413334330118545	-0.0213055112273866	0.0281390978100160	
+2.6680000000000001	0.0246706505400780	9.8102839208383497	-0.0046215540010068	0.0338037428702332	-0.1019544056118579	-0.0959624956256544	
+2.6690000000000000	0.0249746438038146	9.8390242447786065	0.0069017110334412	0.1570291365391266	0.0565540831929104	0.0366749072395127	
+2.6699999999999999	0.0182497550694118	9.8490609118819652	0.0139288235334638	0.1633426172415128	-0.2209445882188876	0.0166637903332462	
+2.6710000000000003	0.0284922879668318	9.8075902663224355	0.0076197503339176	0.1745109832682565	-0.1082467071609212	-0.0386021228644322	
+2.6720000000000002	0.0488446656010084	9.8140838071139758	0.0164133665767746	0.1151686953341801	-0.0012638264606435	-0.1237529961614865	
+2.6730000000000000	0.0334572250180418	9.8234146724209399	0.0335263689202013	0.1770117171867789	0.1824677844101153	-0.0635934746864662	
+2.6739999999999999	0.0261884223861473	9.8216183222128102	-0.0031409135411305	0.2500405897210167	-0.2440112618950999	0.2220432173452666	
+2.6750000000000003	0.0230150325978079	9.8165733525521723	0.0116327652767307	0.0944029676417248	0.2302556314893055	0.1503125494865477	
+2.6760000000000002	0.0327936804742956	9.8297244154027723	-0.0062673765094093	0.0587903515019670	0.0840385229771520	0.0541700321946190	
+2.6770000000000000	0.0339883609493639	9.8297536062932487	0.0028408991073331	0.0961212970892776	0.2084878350636546	0.0656652479800325	
+2.6779999999999999	0.0340344659606197	9.8245217953521191	0.0134792857616375	-0.0346148251306390	-0.0539013234052931	-0.0661334781798582	
+2.6790000000000003	0.0287260353018309	9.8293140771893341	0.0079938017467385	-0.0826033676301287	0.1378378218328576	-0.3186018524255593	
+2.6800000000000002	0.0338044876486810	9.8217659018450458	0.0083065157088914	0.2507337736397332	0.0585156616310920	0.3024342882562094	
+2.6810000000000000	0.0536052771795407	9.8352195880590685	-0.0142652268314280	0.1372301751889053	-0.2114856878503650	0.1084647439659100	
+2.6819999999999999	0.0377921040113632	9.8272537378254139	0.0070988205992182	0.3245945781033856	-0.3083653794345942	0.1832038841663658	
+2.6830000000000003	0.0237771086194620	9.8306582500978621	0.0125359954363448	-0.0436124573839736	0.0190098915775091	-0.2239143537821558	
+2.6840000000000002	0.0242340926196622	9.8235667145206396	0.0143872098941473	-0.2186935493195182	0.0880997628568947	0.1837919974961227	
+2.6850000000000001	0.0282378008186356	9.8429038384712353	0.0099306653338610	0.1578214232630197	0.1199422986884874	0.0410292812749907	
+2.6859999999999999	0.0395719517540965	9.8162078804150674	-0.0057192145416755	0.1556321540427277	-0.1051049737685536	0.0215743524061011	
+2.6870000000000003	0.0678137170818561	9.8732694297631234	0.0068854519316104	-0.1816346374761073	0.3058750402463818	-0.0392674847373382	
+2.6880000000000002	0.0318868035939169	9.8154421157352321	0.0159668826605291	-0.0508048675687892	0.0569184567103680	0.3103074304642948	
+2.6890000000000001	0.0523179056848701	9.8353336463534475	-0.0004785906295706	-0.0560998774672455	0.1648130542038128	-0.0167223268323486	
+2.6899999999999999	0.0334527771531699	9.8266348116667572	0.0158328308939403	0.3027843074809372	-0.0513558360586410	-0.2094302502889470	
+2.6909999999999998	0.0327390345460423	9.8481085904622496	0.0058001346586381	-0.3558226385467406	0.0958258336998320	0.1973805905706781	
+2.6920000000000002	0.0424404563911990	9.8270462822625007	0.0193359142863433	0.0586986779485344	-0.1526138246138304	0.0744086598362051	
+2.6930000000000001	0.0208002326958312	9.8240599828404189	-0.0182976685878361	0.1098609418608938	-0.1665845795318286	0.1446367815596596	
+2.6940000000000000	0.0461613960535648	9.8284175492429995	-0.0079618398638818	0.0813719756911193	-0.0590823626228999	-0.1837195441669796	
+2.6949999999999998	0.0168498004100779	9.8285763418440872	-0.0180291358155548	0.0900712114643175	0.0102044194548693	0.2356703678570776	
+2.6960000000000002	0.0595430156357642	9.8440599224241794	-0.0034896130466761	-0.1358699803481913	-0.0387498357059013	0.0560025920834966	
+2.6970000000000001	0.0288211615706377	9.8310247133558306	0.0222923980478106	0.2636487499311185	0.0445934909133235	0.2850424856471939	
+2.6980000000000000	0.0256251947561576	9.8198861539540729	0.0066557528462984	-0.2463333235339863	-0.3811787935659512	-0.0131667157853286	
+2.6989999999999998	0.0283770681436344	9.8125149550540858	0.0056801451030017	0.2763928107553136	0.0892638663970880	0.2144227569458257	
+2.7000000000000002	0.0300662920199433	9.8349544606598869	0.0033098544624423	0.2115368140796303	-0.1391216411669580	0.2041607041402245	
+2.7010000000000001	0.0323073354166609	9.8255533500276453	0.0023787529676574	0.0570549653407480	0.0936038113984005	0.1896100153125070	
+2.7020000000000000	0.0376380182305016	9.8433177705003363	-0.0118156025186242	-0.2261807388407732	-0.1864598819567861	0.1511509121237936	
+2.7029999999999998	0.0177894037860646	9.8337902738275744	0.0144364021824538	0.0101798047432427	0.1084981585397117	-0.2448582796661712	
+2.7040000000000002	0.0284971629721802	9.8248686219122749	0.0090729593776808	0.2184691086144799	-0.1792776587058184	0.2693744276977729	
+2.7050000000000001	0.0388136666550140	9.8151800777061329	0.0090403272368346	0.1139204357491202	-0.0112404186349317	-0.1165616774753747	
+2.7060000000000000	0.0426839808814038	9.8197761459626705	-0.0043794267474516	-0.1398185521204807	-0.0033241407835904	0.0943509337381414	
+2.7069999999999999	0.0218239125960246	9.8367378185055738	-0.0060721703339461	0.0992612172467206	-0.1305673410372056	-0.0043591663129335	
+2.7080000000000002	0.0228523394313417	9.8113209884665729	0.0118514786626329	-0.0350366873493775	-0.0728309268665854	-0.0166453037996745	
+2.7090000000000001	0.0518832275198109	9.8237105038039392	0.0125986625655474	-0.2017607789249461	-0.0582914583996880	-0.1259199013770606	
+2.7100000000000000	0.0309036477678325	9.8357604196739690	0.0088463596075822	0.0993823577686300	0.1755928250456337	-0.0932108357427411	
+2.7109999999999999	0.0335538243681313	9.8140457370730374	-0.0043485603072341	-0.1253839963266663	-0.1001393570256540	0.0485968045782901	
+2.7120000000000002	0.0377887031827452	9.8013141000767003	0.0042853566534583	0.0494902588179163	0.0979790128681167	-0.0051205656542972	
+2.7130000000000001	0.0427840198836121	9.8203582343754707	0.0088600081901740	0.2071932865634726	-0.0116970628512151	0.1880827158036882	
+2.7140000000000000	0.0307088671802906	9.8243885868972392	0.0059124066911454	-0.0309108330384814	0.0506491732982059	0.0652295482703351	
+2.7149999999999999	0.0156721311619824	9.8234532868328017	0.0088403629795601	0.2615566922698799	-0.1991419539988176	-0.0766557417224228	
+2.7160000000000002	0.0364598756270989	9.8373160005527698	0.0285867637874821	0.2494774733791191	-0.0174911366290365	0.1677536448304898	
+2.7170000000000001	0.0362192718601566	9.8325457060820067	-0.0022865025827046	-0.1805291126360919	-0.3370291688688042	0.2464531553321697	
+2.7180000000000000	0.0256048647224385	9.8510881796178964	0.0056368657827150	0.1045749878423481	0.0030276315802267	0.0403278374989890	
+2.7189999999999999	0.0329273181392327	9.8363449016394746	0.0254386266311872	-0.1878356824480490	0.1598074249013312	0.1020018922443871	
+2.7200000000000002	0.0283628441586288	9.8353592213811289	0.0014267077134639	0.0979152761238045	0.0331484065078903	0.1043087356697479	
+2.7210000000000001	0.0419944919073052	9.8232519707304053	0.0093657666196915	-0.1002903861537674	-0.1636806742697089	0.0377601358290804	
+2.7220000000000000	0.0351072642689982	9.8316807796300871	0.0026967980053965	0.0417586651743926	-0.0120322710903001	0.0392642302354485	
+2.7229999999999999	0.0488501167855685	9.8145992753780238	0.0238854403770036	0.4721609985130646	-0.0252637499099254	0.5414767735278990	
+2.7240000000000002	0.0299076016559492	9.8327972041980214	0.0059428570328833	0.2740498910704833	-0.1778722869872846	0.1380791936593923	
+2.7250000000000001	0.0283907967856535	9.8133104859204785	-0.0017671929420934	0.1734323718166781	0.0116641229953722	0.1964966893758802	
+2.7260000000000000	0.0247776133875643	9.8160377136648016	0.0008298805614283	0.2319921264587058	0.1640358197343599	0.1314384517054192	
+2.7269999999999999	0.0355182316809707	9.8207867015127590	-0.0004262088924177	-0.0469399592542112	-0.0077080857224135	0.2346342294165109	
+2.7280000000000002	0.0320507017372367	9.8466401651873081	-0.0011627790987396	-0.2195595770201962	0.1985800865386414	0.0449965931633629	
+2.7290000000000001	0.0357492146501103	9.8332362439057768	0.0065285498545269	0.0018677582547237	0.0576980321346059	0.3514863025861976	
+2.7300000000000000	0.0345530646035132	9.8212046824901780	0.0009238751962095	0.0612762007678406	0.1362029623797725	0.0716933072853412	
+2.7309999999999999	0.0168276146446286	9.8490190457911062	0.0162760876395887	0.2326575608866954	-0.3753119240191427	0.1446102114305179	
+2.7320000000000002	0.0092488912245969	9.8188034828189092	0.0110718372037881	0.0543108464840751	-0.0618466940138297	-0.0385948676516755	
+2.7330000000000001	0.0646161174498295	9.8286127480963614	-0.0096037383292484	0.3134009246394912	0.1317062827470745	0.1977799763132449	
+2.7340000000000000	0.0216590241335742	9.8085356868633955	0.0038317969685940	0.0594796340811045	0.1865651731033338	-0.0901440745427926	
+2.7349999999999999	0.0294773493515213	9.8050577307973050	0.0048352159041508	-0.0712392489450855	0.0010651375933812	-0.0421820944143876	
+2.7360000000000002	0.0436183888169714	9.8382552307007867	0.0112030561162616	0.1743056523468700	-0.0599019949527749	0.2316991802752342	
+2.7370000000000001	0.0044241108928896	9.8045564766527971	-0.0010425591766619	0.1523341019931849	0.3652925370950547	0.0450492207722863	
+2.7380000000000000	0.0229706531279970	9.8302297083700569	0.0138050494666497	0.0108190534266514	-0.2796383614459640	0.2795223303245196	
+2.7389999999999999	0.0501474536808194	9.8382217673403698	0.0000374931083540	0.1733535520760413	0.1122426372310376	0.2097508859129423	
+2.7400000000000002	0.0196721919446744	9.8525055899562979	0.0040154459307393	0.1541490868535086	-0.0087356602128961	-0.0580405425330686	
+2.7410000000000001	0.0197406882380401	9.8413761569155120	-0.0078576708833092	-0.1787003416484743	0.0651016763265279	0.0766441109249872	
+2.7420000000000000	0.0415324712811815	9.8268795510002018	0.0296479951857052	-0.0778663321760992	-0.1928288629107943	0.2175442478325051	
+2.7429999999999999	0.0248031175604421	9.8329124169950965	-0.0111596586727825	-0.0313640602283239	-0.0575312225063049	0.2118941898469452	
+2.7440000000000002	0.0328582809727592	9.8302680188153175	-0.0042484020617096	0.2425858099854585	-0.1206351659177589	0.2189680144916791	
+2.7450000000000001	0.0259170531773203	9.8338610026835465	-0.0019848866110446	0.1160150585706543	0.0667516123321850	0.2912888835264572	
+2.7460000000000000	0.0442991907087551	9.8279806748351195	0.0150591562842638	0.1047245473993634	0.0432401736740620	0.2008297709274569	
+2.7469999999999999	0.0378770091608020	9.8239458387521328	0.0124098892504333	0.0260609747718991	0.0925377518627221	0.1392966765062973	
+2.7480000000000002	0.0243851691648174	9.8218589562437799	-0.0023270222046033	0.0987043918592934	0.0538147396656874	-0.1044629738482913	
+2.7490000000000001	0.0285458030934527	9.8238706478713613	0.0234617550426884	0.0152804695768225	0.0408037577705299	0.4122789069601054	
+2.7500000000000000	0.0057910999593807	9.8286491036712178	0.0023665280113435	-0.1174366169395876	-0.1938596418474036	-0.1143972644981890	
+2.7509999999999999	0.0269720200667748	9.8264168097505866	0.0072181487382070	0.1044135955228282	0.0229711370909581	-0.2858950404261377	
+2.7520000000000002	0.0195978803135956	9.8116523649327139	-0.0121460395635507	0.0750560611745211	-0.0841432378700551	0.0369246941558964	
+2.7530000000000001	0.0349346455515942	9.8259321507261870	0.0221847535815811	0.0680934167503979	0.1130606073204448	0.1058984069527896	
+2.7540000000000000	0.0341120954666292	9.8150719203935246	-0.0050396970539280	0.0990618464777546	-0.1825342180438770	0.3625705542212049	
+2.7549999999999999	0.0464839552542606	9.8274648308182790	0.0026225081885484	-0.0055180838006104	0.1464134790190499	0.0586070303968763	
+2.7560000000000002	0.0435863339226970	9.8426896736346698	-0.0027573569304827	0.0581994225471652	-0.2028134781431757	0.2021094993929971	
+2.7570000000000001	0.0331302964037712	9.8321423413943130	0.0221511390296091	0.2097130935796435	0.0177682161589062	0.1391047378482828	
+2.7580000000000000	0.0388795917711003	9.8260792895169828	0.0209233228334725	0.2243428434030743	-0.1533848776147851	0.0060614551045130	
+2.7589999999999999	0.0373431647474837	9.8374855896003286	0.0085088408159998	0.0121913889487631	-0.0365124444508181	0.0182210551118437	
+2.7600000000000002	0.0325473984525479	9.8297359201425909	0.0047626234696805	0.0443760176737095	-0.0616012272088336	0.0848356818953086	
+2.7610000000000001	0.0286552141322828	9.8270439797296429	0.0234425382487625	0.0771500333492008	-0.0393392331615205	0.0520535927052625	
+2.7620000000000000	-0.0082409171201548	9.8280390540378999	0.0097303478413593	0.2180289772913118	-0.1742825055599995	0.1302740880700558	
+2.7629999999999999	0.0426457280331853	9.8239260480800858	-0.0023488926337617	-0.0954029738754871	0.1042734611037701	0.0030211436466414	
+2.7640000000000002	0.0354619053227571	9.8301908887634184	0.0064187599441586	0.0110216822324778	-0.1251539657993604	0.1928119493046599	
+2.7650000000000001	0.0546524341744920	9.8216440871387203	0.0031525338201874	-0.0083861280493617	-0.0589399861983241	-0.0894473932176506	
+2.7660000000000000	0.0413202137500486	9.8380758577560332	-0.0053686130522669	0.2470001026040735	-0.1668727100180386	0.3524918126268687	
+2.7669999999999999	0.0386766306887384	9.8373159709624787	0.0175858183825255	0.1516974767393792	-0.1128558305093008	0.0007521452425749	
+2.7680000000000002	0.0269603850941991	9.8329311767943874	0.0130052562782254	-0.0207532308617743	-0.2241691951285968	0.0210872193281135	
+2.7690000000000001	0.0400050067828787	9.8225986606710869	-0.0038391587345424	-0.1946693012801741	-0.1109596913374897	0.3364985397532019	
+2.7700000000000000	0.0270897067971379	9.8246148786636560	-0.0076439658367647	0.0278143321086039	-0.1834963889502191	0.0546107283775322	
+2.7709999999999999	0.0276178651723578	9.8204400347160821	0.0035073826855052	-0.0003875335567231	-0.0075612610916553	0.3718499811876951	
+2.7720000000000002	0.0281019563432253	9.8048360750505577	-0.0025182753126963	-0.0674962544652515	-0.1316609395882395	0.1826944869840516	
+2.7730000000000001	0.0407505881372439	9.8405823106690651	0.0025150993163576	0.1052689514390864	0.0557466758504221	0.2237435762114347	
+2.7740000000000000	0.0260075938828665	9.8311375920855806	0.0083062420340792	-0.0267785267945605	-0.0250770848299580	-0.1621926939586298	
+2.7749999999999999	0.0307777024713814	9.8217278549345632	-0.0098753584776197	0.0368416904309575	0.3304034667229908	0.0087450409269930	
+2.7760000000000002	0.0243929340749363	9.8325457922903485	0.0058088156091199	0.1083640643954445	-0.1048651911219924	0.1184831151531208	
+2.7770000000000001	0.0260089983197546	9.8251650391556069	0.0058055417101426	0.0998480215803942	-0.2376314448039691	0.0332139165050886	
+2.7780000000000000	0.0242249977624683	9.8270415583030637	0.0063712246835959	0.0274841492068179	-0.0081108573134766	0.1897013787467894	
+2.7789999999999999	0.0425975206567048	9.8128521052167113	0.0214122422683354	-0.0516735652289933	-0.1688336862116037	0.1651330035489108	
+2.7800000000000002	0.0154312824612888	9.8208130182453885	0.0219360490869060	0.1002284181189808	-0.2068261232762330	0.5764695282519017	
+2.7810000000000001	0.0366642710091836	9.8202204437505465	0.0019657740033479	0.0320207330555742	-0.0262121525491477	-0.0251895600520787	
+2.7820000000000000	0.0194272431166766	9.8383733891370149	0.0015303686900797	-0.1318197453538371	-0.2288863978362966	-0.1860940540862921	
+2.7829999999999999	0.0308245645510167	9.8593560504222033	0.0048634356561910	-0.0633720552629838	0.0726112467479766	0.0433878716485020	
+2.7840000000000003	0.0328413242352746	9.8016288927895445	0.0000961786652360	0.1274346861890259	0.1418874783797726	0.1514658171449452	
+2.7850000000000001	0.0301644137959196	9.8262900142243783	-0.0064535637031754	0.2412536400433234	0.1276409822656656	-0.0727069525402920	
+2.7860000000000000	0.0277100296743817	9.8434555553799825	0.0052479140355425	0.1512222598098744	0.1049078960843835	-0.1683744300873750	
+2.7869999999999999	0.0305583808768052	9.8276498808775425	0.0088367644646630	-0.0749902557109650	-0.2253717152944403	0.2293585880795124	
+2.7880000000000003	0.0318265259367387	9.8265480922870481	-0.0063166441559066	0.2876821380210590	0.0789995080522679	-0.1272703105544661	
+2.7890000000000001	0.0366526403155755	9.8338723099927794	0.0079127962391160	0.0453500270124124	-0.3522358906707633	-0.0596611070893922	
+2.7900000000000000	0.0364251740926809	9.8159380888223478	0.0162704390168326	0.1348773795769291	-0.0749362692053024	0.0922418838451584	
+2.7909999999999999	0.0139064157041971	9.8319211297767257	0.0306365657181301	-0.0496850099984158	0.2156300603834056	0.1876510050704699	
+2.7920000000000003	0.0211475308691976	9.8210791998538944	0.0243630641098249	-0.0139348448947201	0.0610740134023453	0.2723897280434336	
+2.7930000000000001	0.0436562019899376	9.8380532408827204	0.0135754803199627	-0.0815778973739316	-0.0295945879073537	0.2010595271204770	
+2.7940000000000000	0.0372829882438085	9.8209402477251135	-0.0189264416684657	0.0215321353814596	0.0188143605924891	-0.1241515576188075	
+2.7949999999999999	0.0245546134233557	9.8318602881714128	-0.0043673345686099	-0.2986275453517691	-0.1684307258505836	-0.0636227055285619	
+2.7960000000000003	0.0561327851217426	9.8108742535649061	0.0131456426676380	0.0637075434533712	-0.1916159247186393	0.1074964173730045	
+2.7970000000000002	0.0405628116898936	9.8343867105976130	0.0138248566972515	0.0454779305160850	-0.2312813273737791	-0.0500324306822343	
+2.7980000000000000	0.0319149681464352	9.8276775846880735	0.0116428760639637	0.1177263178601970	-0.0767312704792101	0.3991082908458986	
+2.7989999999999999	0.0371062421871060	9.8339063413923373	0.0175880311545573	0.0773428921667303	-0.0843883407873519	0.3737542154834752	
+2.8000000000000003	0.0355395388513220	9.8408187071147992	0.0066197266521727	-0.1887360924056016	-0.1317489684189687	0.0070314720818802	
+2.8010000000000002	0.0318765726999147	9.8179529941997767	0.0160460508667483	0.1088014879733522	-0.1363661637344764	0.1284085844805660	
+2.8020000000000000	0.0478230733696193	9.8510159710269836	0.0248051573806528	0.0983415943887942	-0.0962870520298915	0.3758880112910938	
+2.8029999999999999	0.0134903064980346	9.8127896578521518	0.0152249763968407	0.0141342376027607	-0.2594643200953016	-0.0604214929453513	
+2.8040000000000003	0.0341000934539911	9.8155617800179265	-0.0036533828862741	-0.0403560533861618	-0.1580695889713433	0.0616231238391640	
+2.8050000000000002	0.0444281985333773	9.8118792027861037	-0.0097472346868283	0.1235668234465761	-0.0125463852160812	0.0844036070021526	
+2.8060000000000000	0.0386490057360055	9.8214221966749946	0.0108905653708107	0.0829601108809936	0.0297767510471282	0.2082044823362545	
+2.8069999999999999	0.0304542319058351	9.8227365012902830	0.0167547341390947	0.0051127264152633	-0.0847479877322958	0.1583368427813885	
+2.8080000000000003	0.0236435905212996	9.8405087820025550	-0.0002618139999374	0.1028531485566098	-0.1037995145969481	-0.0182261791551969	
+2.8090000000000002	0.0311937830709957	9.8256640461105711	0.0066684549605259	-0.1416415254880088	-0.0495905610561039	0.2293805694016351	
+2.8100000000000001	0.0398850895675522	9.8312396127135742	-0.0068998377182643	0.0584784163440401	-0.0937198455561588	0.0571894577186085	
+2.8109999999999999	0.0123150526750735	9.8391825584317179	0.0244972322294039	0.0817571843474278	-0.0363933500824188	-0.0042358227786259	
+2.8120000000000003	0.0431560973547566	9.8196254613870142	0.0194362984485835	0.0645757804420253	0.1168703247788050	0.0292704100219589	
+2.8130000000000002	0.0390061797210490	9.8327647695136058	0.0262707635018155	0.0596571575000474	0.0090978150099719	-0.0324341054434444	
+2.8140000000000001	0.0318289651584034	9.8364801244548605	-0.0197550495388839	0.0931099068096121	-0.0759357222967235	0.1949293697577225	
+2.8149999999999999	0.0223645755954212	9.8284783871755401	-0.0154799139136076	0.0261202960680217	-0.2638450121593799	-0.1940710258812871	
+2.8159999999999998	0.0501774665448624	9.8115093445447457	0.0005421390422546	0.0653602458682780	-0.0983028739758530	0.3308073616304346	
+2.8170000000000002	0.0379051161840530	9.8083571861306549	0.0120880220879513	0.2023842435831054	-0.0430361293497421	-0.0658998093392053	
+2.8180000000000001	0.0341212067997109	9.8286478596917846	0.0129017553493440	-0.0587827335596496	0.0384323969516670	0.0464366845692288	
+2.8190000000000000	0.0265099257032785	9.8254248549631367	0.0123077836391141	0.0205160512846902	0.1335463872992054	0.2248289289941028	
+2.8199999999999998	0.0600843684701245	9.8086157557200959	-0.0077967384277167	0.1434887333425560	0.1720415607537786	0.0678313267996757	
+2.8210000000000002	0.0222906980704312	9.8009215987111933	0.0036404471629542	0.1705531530875132	0.1882421508592628	-0.0057645967173860	
+2.8220000000000001	0.0246076080885016	9.8166383154233294	-0.0027610809404546	0.3504503232452063	0.0551158539278686	0.1391018144155115	
+2.8230000000000000	0.0299972084028156	9.8416481386452368	-0.0027723281118376	0.3588444357954449	-0.2563687788416800	0.0675346702105217	
+2.8239999999999998	0.0284161797635261	9.8249181380764874	0.0145849456532889	-0.0457715161801852	-0.1731973256055435	0.1057373030008017	
+2.8250000000000002	0.0208200682940686	9.8242187867149831	-0.0009630852123862	0.2964743420614929	-0.1796105710153406	0.0510315688494268	
+2.8260000000000001	0.0431137578074946	9.8162079015334278	0.0158760569904783	-0.1589559617672717	0.0699860072897630	0.0847433339204583	
+2.8270000000000000	0.0306193224743912	9.8172484740807509	0.0022562586287405	-0.0616336156609421	-0.3127040427099133	-0.4080383276975092	
+2.8279999999999998	0.0366481472648015	9.8208964725082577	0.0191347013675665	-0.0273150008507876	0.2707666461935775	0.2419019565824451	
+2.8290000000000002	0.0232555952447922	9.8398737576232893	0.0067961731082470	0.1866610980504014	-0.1624866434738759	0.0738696316583966	
+2.8300000000000001	0.0485338838342335	9.8365696955695334	0.0203246889779932	-0.0392535560298866	-0.0223521096349802	0.2718352266342354	
+2.8310000000000000	0.0124517104404380	9.8261995060882530	0.0032016290940630	-0.2356508167474527	0.0754803478414272	0.2161900128394235	
+2.8319999999999999	0.0483187387421373	9.8237749032943746	0.0018319328105403	-0.1126856888051258	0.0719022561378838	0.1633933314839338	
+2.8330000000000002	0.0308198596830226	9.8299552281319134	0.0035022998105055	-0.0244526117038452	0.1785408128038305	0.1534685082632333	
+2.8340000000000001	0.0255941692276873	9.8405432617313746	-0.0041819859364626	0.0641934504862844	-0.2306673231914433	-0.0957162324382780	
+2.8350000000000000	0.0431632818400141	9.8255735403223188	0.0060852131125183	0.0111378257107794	-0.0617767424264226	0.2543918872713808	
+2.8359999999999999	0.0445306527232753	9.8281530793728802	0.0107497010220224	-0.0660634361829632	-0.0353678574278776	0.0166369686306022	
+2.8370000000000002	0.0432127513106806	9.8112434999555997	0.0318137427581654	-0.3123836812880573	-0.0583964767639681	-0.0779771166601974	
+2.8380000000000001	0.0428257716683285	9.8246019117546197	0.0168886948025644	-0.2171568987938190	0.1083731620486954	-0.0090507255865519	
+2.8390000000000000	0.0537745725991162	9.8105069200792006	0.0044698919095131	-0.0113945194259502	-0.1539792062792295	0.2233279829174563	
+2.8399999999999999	0.0241595510992458	9.8177015139951624	-0.0006374153258853	-0.0057776028301737	0.1670483600827126	0.0170447114282001	
+2.8410000000000002	0.0457055604221303	9.8143102671937701	0.0094566203411499	0.0572804897536934	-0.1702973714138959	-0.0679379044817399	
+2.8420000000000001	0.0406655827232660	9.8305968780239716	0.0228740338658838	0.1479274616449361	0.0323777419469659	-0.1310878188331395	
+2.8430000000000000	0.0437484484855719	9.8191328386648475	0.0128349003426545	-0.0367950709772742	-0.0978304638719936	0.0675772813296631	
+2.8439999999999999	0.0425585727608624	9.8269128889241681	0.0366174374606436	0.1685288451047567	-0.1502062940618787	0.0266346236332710	
+2.8450000000000002	0.0431028343411941	9.8290101792195532	0.0255519183576575	0.0227735180109640	-0.0030893566113535	-0.0849328515038211	
+2.8460000000000001	0.0425072794612421	9.8199738055901129	0.0273404137694868	-0.0559771042324395	-0.2377329382641939	-0.3180804964125417	
+2.8470000000000000	0.0556719164572443	9.8285329296062969	-0.0001931952605849	0.0766624843340249	-0.0547015552385404	0.3216762001083499	
+2.8479999999999999	0.0317066976131036	9.8444445511559042	0.0035171610108835	0.2097465906850022	-0.1729457925543887	-0.1472408585577718	
+2.8490000000000002	0.0302281561722517	9.8300280657303727	0.0279011447978082	-0.2208621797747247	-0.0091667096475378	0.3251232747149650	
+2.8500000000000001	0.0395720022204984	9.8194495687958678	0.0103381514341484	0.2913489393965788	-0.0191070518161036	0.2877251681893260	
+2.8510000000000000	0.0459450458963186	9.8004617745263918	0.0128589216172539	0.0400692883965660	0.0380734948201532	0.0544219634562321	
+2.8519999999999999	0.0313392944273617	9.8150719407601130	0.0024697680258701	0.0626042331961518	0.0349564188858627	0.3147662326605001	
+2.8530000000000002	0.0273749218898279	9.8314801693778957	0.0179711074772658	-0.1955034602953237	0.0288424792471963	-0.0806877180512825	
+2.8540000000000001	0.0536054023412572	9.8310812344975265	0.0151665079956932	-0.0299303913679170	-0.2346859995783315	0.4022664563534730	
+2.8550000000000000	0.0342248949426538	9.8414014076550984	0.0250204699832304	0.3830588873699350	-0.1087827633970946	0.1272158618132035	
+2.8559999999999999	0.0258129145242612	9.8236667891537817	0.0400870616666975	-0.2056989629529745	0.1504706233502252	0.2146165130856185	
+2.8570000000000002	0.0567491814762714	9.8338845043515857	0.0210786563290742	-0.0913341653728008	-0.1022151749531984	0.0773492699078779	
+2.8580000000000001	0.0143124252444013	9.8247163345063715	0.0166287267878344	0.3318761532831178	-0.0098725265922739	-0.1396845409824662	
+2.8590000000000000	0.0239300831885643	9.8428537926805113	0.0196068279237431	0.1123769593701771	0.0129690983479851	0.1434925474384189	
+2.8599999999999999	0.0352313825308773	9.8254154139161969	0.0084967679961574	0.1876275778047299	-0.1001480999059735	0.2153132452813738	
+2.8610000000000002	0.0441170826151227	9.8163667645230035	-0.0190164487441201	0.2177520507103798	-0.0858371804887678	0.0735407823223504	
+2.8620000000000001	0.0350396986777591	9.8024987741593215	0.0076102128554157	-0.1242134574472000	-0.0271454800519663	0.2803641472955475	
+2.8630000000000000	0.0342788971022231	9.8164564730846298	0.0096387786721288	0.0366707982127244	-0.2026819023633362	0.3199101499975323	
+2.8639999999999999	0.0471477461395984	9.8195973771667795	0.0002384607838026	0.3034930435804205	-0.4150244769135678	0.0567499122502070	
+2.8650000000000002	0.0281349882569022	9.8253259210231061	0.0021218189296727	-0.0410704272028917	0.0683732288242062	0.0816767628551143	
+2.8660000000000001	0.0438911979080166	9.8384073056832317	0.0066000650640734	-0.2071527093374837	0.3560065362883670	-0.0205297964054121	
+2.8670000000000000	0.0247581341186216	9.8183102554281767	0.0181944593020237	0.0157326745885617	-0.0256763807203224	0.0099254027718100	
+2.8679999999999999	0.0267355529246160	9.8204609627700634	0.0075990618823261	0.0273730367545644	-0.2907837961566156	0.2005057544745560	
+2.8690000000000002	0.0526558769467896	9.8151631553229723	-0.0034364871730985	0.2117165580409187	-0.0465945487618364	-0.0189405175046290	
+2.8700000000000001	0.0393191677465888	9.8491047093949806	-0.0070293611449361	-0.0239605293999723	-0.2045654731455807	0.0502908387579271	
+2.8710000000000000	0.0317026667404578	9.8112524678963826	0.0238046538869906	0.1193454288801552	-0.0362322057686531	0.2724420440641633	
+2.8719999999999999	0.0346734486050045	9.8226538289372591	0.0050777650652593	-0.2522749132947702	-0.0666604654440795	0.2432278785649580	
+2.8730000000000002	0.0411727025449595	9.8301589855845943	-0.0096798469719062	0.1272695420065855	0.1816712874879423	0.2840130648693119	
+2.8740000000000001	0.0330964690641780	9.8366810469292680	0.0052731175096006	-0.0619615823898039	0.2955366723843897	0.3499097431153471	
+2.8750000000000000	0.0424321615710530	9.8173424602816191	0.0238901817020638	-0.0344657910316764	-0.2208281861726958	-0.0987521102550566	
+2.8759999999999999	0.0425135961864402	9.8168893005263502	0.0147871056089164	0.2464402718037730	0.0405879143443651	-0.1341539185672832	
+2.8770000000000002	0.0457296777460975	9.8244148245873273	-0.0027424291218154	0.1673821895453277	0.1589970621279872	-0.0170929279641559	
+2.8780000000000001	0.0312338751978517	9.8479877006813137	-0.0145351890050434	0.2206886526109883	0.1258594306981109	0.3126566096452966	
+2.8790000000000000	0.0450867525764496	9.8435689180838271	0.0022780050464002	0.0049668024699067	-0.1571364645621756	0.1383809414057883	
+2.8799999999999999	0.0155113135740667	9.8284223514722981	0.0059518233581584	-0.1704769582570630	0.0426679398909240	0.2496818325726675	
+2.8810000000000002	0.0407724683446834	9.8162599605302336	0.0233479771238548	0.0374345360624915	-0.2077452002972223	0.0975004964819381	
+2.8820000000000001	0.0411874650657131	9.8347621436901083	0.0010065947910053	-0.0167832325627415	0.1953039481933921	0.1491952359795600	
+2.8830000000000000	0.0333103508715363	9.8330750276583991	0.0147883859335807	-0.1456954285622564	0.1011091049952214	0.0838871536934503	
+2.8839999999999999	0.0501353661271830	9.8155522759088480	0.0275047338357400	0.2143091075004560	0.1955447412071732	-0.0607395797400275	
+2.8850000000000002	0.0434881002262942	9.8229512927945475	0.0062990583257547	0.0242132865309285	0.1120045112080683	0.2475055786399235	
+2.8860000000000001	0.0072398794417978	9.8250052720632333	0.0113070875306773	0.5365225950389880	-0.0377588464062619	0.1183782044022424	
+2.8870000000000000	0.0313076139486443	9.8209849427055733	-0.0009196605103241	0.0546894271515198	-0.0484929731569727	0.1568106114599292	
+2.8879999999999999	0.0441037435497786	9.8126895049598843	-0.0117020288104074	-0.2070781602903096	0.0589990004581755	0.1955460570417853	
+2.8890000000000002	0.0558955223328665	9.8231738402343485	0.0082074765813112	0.0799586979027233	-0.0328887821979827	-0.0297572273848998	
+2.8900000000000001	0.0263123296612992	9.8177396524012970	0.0002300172788463	0.0804834662771616	-0.2966126814707715	0.2754906431964513	
+2.8910000000000000	0.0190516260942958	9.8454948816794801	0.0057096167563401	0.1853537476326532	0.2942677356336986	0.2668008379829991	
+2.8919999999999999	0.0282475075795303	9.8226292345996651	0.0051547561327973	0.1826856331971559	0.0157857964633668	-0.0007615858024986	
+2.8930000000000002	0.0370211315772473	9.8087612415618910	0.0002490455147002	0.0446682954970256	-0.0331544954282485	0.2300807595859298	
+2.8940000000000001	0.0482556419354903	9.8165324765172670	0.0059099248333402	-0.0616302040730593	0.1062629974964643	0.0359764137427736	
+2.8950000000000000	0.0389432989980278	9.8253210752388362	0.0280287378707338	0.1471810902741317	-0.2068428781692811	-0.0646930539989791	
+2.8959999999999999	0.0216146203767545	9.8281221077324989	0.0156926606444975	-0.0222490457305715	0.1643462123243618	0.1025337227409899	
+2.8970000000000002	0.0465174180554623	9.8293846780434642	0.0025658600073664	-0.2822628965028496	0.0943084561225251	0.0514212595124225	
+2.8980000000000001	0.0391979749227109	9.8379644742300130	0.0164546208905923	0.1572304689111933	-0.0686168994597771	0.1156657662575279	
+2.8990000000000000	0.0397922761504188	9.8153416429190923	0.0063963340066246	0.1342536733653793	0.2303789396575235	0.3334516080323193	
+2.8999999999999999	0.0323451177784581	9.8176355214857587	-0.0089374275647635	0.0772125050118202	-0.2463247644597707	0.1506361141629999	
+2.9010000000000002	0.0226640878110608	9.8175809907866007	0.0036025731425785	0.0082797696620593	0.2381443977854339	0.2109905534945592	
+2.9020000000000001	0.0200563785519551	9.8279490985932405	-0.0052162471463130	0.1831028784634161	0.0795841357612063	-0.0101781078292518	
+2.9030000000000000	0.0533317895223242	9.8342981660469011	0.0148217892946697	0.1505726299826824	-0.0062394781255070	0.1749169111171632	
+2.9039999999999999	0.0258006671942221	9.8403416708874794	0.0097834598826026	-0.0341091179005016	-0.0514513996270232	0.3191140073930079	
+2.9050000000000002	0.0262324239806961	9.8184967250400934	0.0206682773401772	0.1374394530631026	-0.1141635246114504	-0.0420578888355975	
+2.9060000000000001	0.0482011416136814	9.8231519096044924	0.0190209721520674	0.1669906561884021	-0.1713435964893902	0.3136172888863445	
+2.9070000000000000	0.0380059773852927	9.8087660880700120	0.0104614482602730	0.0005299737804650	-0.2634584725644940	0.0516752760235370	
+2.9079999999999999	0.0507349992329998	9.8217018659959958	0.0146758241401619	0.0535259454205090	-0.0325701595937868	0.2089245188217961	
+2.9090000000000003	0.0100572923336371	9.8349006441518778	-0.0070175286251809	-0.0202915838807187	-0.0847993689551449	-0.1915781650089585	
+2.9100000000000001	0.0371138856267864	9.8208706819549203	0.0018220263391400	0.2113900465935059	0.1010528401187942	0.0896275788762122	
+2.9110000000000000	0.0287297620887686	9.8143351037722155	0.0147482124785291	0.1939875168690568	0.0549435248213930	-0.0245161681744614	
+2.9119999999999999	0.0231107134673735	9.8251076040746490	0.0072335096315030	-0.0294369973708394	-0.1665730618919153	-0.0108374570274651	
+2.9130000000000003	0.0249982824153160	9.8188989457874065	0.0130610479580858	0.1785172502548462	0.0902484654058764	0.1178895612597944	
+2.9140000000000001	0.0558459046921484	9.8289676496732792	-0.0087456531685247	0.0397924894562224	-0.0428269058620386	0.3289127428137676	
+2.9150000000000000	0.0235792613813667	9.8205528280803769	0.0234050660851354	0.2281773480169471	-0.2505604166627176	0.1112815223342881	
+2.9159999999999999	0.0343010391330270	9.8348517779770557	-0.0065234608410026	0.1858088847603380	0.2667969436623721	0.0558370249004615	
+2.9170000000000003	0.0395632972605139	9.8156243300107597	-0.0132148749017078	0.1010490380258629	-0.0826226520920022	-0.1838880175059813	
+2.9180000000000001	0.0270874376598433	9.8433290720460835	0.0134374347430505	-0.0546710851833853	0.1872312516798963	0.1909519105725020	
+2.9190000000000000	0.0192473419161615	9.8328818163263882	0.0155514449226700	0.1563030693461409	-0.0297061324337903	0.3587427883736096	
+2.9199999999999999	0.0532868688961628	9.8517556532282757	0.0061960926574295	-0.1670375509052454	-0.2127191507075695	0.2033886233616772	
+2.9210000000000003	0.0420555675009894	9.8138228345258920	0.0161583803566314	0.2797592990489277	-0.0183574037540928	0.1638796212240194	
+2.9220000000000002	0.0343330605236181	9.8119679483699969	0.0108229730506322	0.0025417404118620	-0.1165712519847351	-0.2052611969758013	
+2.9230000000000000	0.0338534148403069	9.8225720273033836	0.0072646418252072	0.1321982895452388	-0.0732579317742804	0.2092106209640672	
+2.9239999999999999	0.0394878760767357	9.8146172448255715	0.0042429175964512	-0.1809948160283691	-0.0923168145281240	-0.0352890067305092	
+2.9250000000000003	0.0280285980951781	9.8132437627583009	0.0266135052583902	0.3036420395501028	-0.1189274813753205	0.0395507495292117	
+2.9260000000000002	0.0189732074669851	9.8188126324335379	0.0125437169577803	-0.0566438053876166	-0.0308526730034134	0.0112405427198083	
+2.9270000000000000	0.0322580150947461	9.8249704648061034	-0.0121563648995469	-0.0051114301943261	-0.1213459036377185	0.4476149700294245	
+2.9279999999999999	0.0237387891025032	9.8064248869878821	-0.0058924929315517	-0.0539737086499681	-0.0462081364749804	0.1069050392557636	
+2.9290000000000003	0.0508393380955590	9.8377614681201990	0.0119466677839948	-0.2081669675246601	-0.1854729883534862	0.0379949289712675	
+2.9300000000000002	0.0255142857079415	9.8452150564994056	0.0091534164525882	0.0206838120792031	-0.2639081831655149	-0.0225402789065009	
+2.9310000000000000	0.0219044792776157	9.8160586264499319	0.0095889680086264	-0.0570740454413155	-0.0043033280825025	-0.2855099692239558	
+2.9319999999999999	0.0184154979642241	9.8242101235635815	0.0074938704423221	-0.0936452555780399	0.1207807192014287	-0.3782940882659611	
+2.9330000000000003	0.0274629074505172	9.8245928486885745	0.0319306317399516	0.0899523478136781	0.1494732322476754	0.0202826235343232	
+2.9340000000000002	0.0345530869022537	9.8340982276974831	-0.0157465200207525	0.3343385673415464	0.0180011894685908	0.0628964333761233	
+2.9350000000000001	0.0452322421164748	9.8402247722944161	0.0193348170248169	0.0286140459451410	0.0039956286719118	0.1219986776568534	
+2.9359999999999999	0.0402991893119474	9.8389220817262419	-0.0045543060893448	-0.0421445126528131	0.0011631091771113	0.0313875951583525	
+2.9370000000000003	0.0512973374064493	9.8294243072604157	0.0121461482183174	-0.0638753182667641	-0.0197259755422573	0.2607875684440996	
+2.9380000000000002	0.0306965973856264	9.8284169227662357	-0.0093624325371871	-0.0968183567991584	-0.0815377468382545	0.3778306796148661	
+2.9390000000000001	0.0532766529264727	9.8073611023029788	0.0045347201903276	-0.0247887235555596	-0.1364437889771120	-0.0350316843543726	
+2.9399999999999999	0.0445267391879413	9.8341290000208605	0.0108584780263449	0.2217488968611858	-0.0526007483020658	0.0427813602439933	
+2.9410000000000003	0.0496807318741312	9.8030626673686942	0.0117759343437332	0.1100947836146505	0.2818904200577789	0.1212122209226576	
+2.9420000000000002	0.0418990806337079	9.8368446057688779	-0.0155853721557662	-0.2142651059423858	0.0278251350329371	-0.0333199890345443	
+2.9430000000000001	0.0223129150911689	9.8408343613124387	0.0041216585936446	0.2306681565290606	0.0612242711421760	0.0284824390937479	
+2.9440000000000000	0.0369225334560734	9.8219883948342215	0.0217243750104149	0.1498764054717402	0.1284466224223483	0.2401979573788530	
+2.9449999999999998	0.0288364205352996	9.8247730396031550	-0.0032533799183620	0.2843671906666174	0.2492213471743101	0.0342464789412986	
+2.9460000000000002	0.0544358083940349	9.8173073564711348	0.0020194877283976	0.0410527836542933	0.2151633677975437	0.2720989038159768	
+2.9470000000000001	0.0191845598253145	9.8158778794231392	0.0030478724203682	0.0997975148485353	0.2098500382473346	0.3206922676808420	
+2.9480000000000000	0.0297185278117202	9.8406741097310029	0.0128176299550325	0.3629992655034940	-0.1052489402186976	0.2334933524522539	
+2.9489999999999998	0.0436175971667595	9.8255673995012085	0.0196272571194210	0.1456731865415865	-0.0021758903025640	0.1431316419526070	
+2.9500000000000002	0.0516480859601078	9.8270125369827070	0.0007581355312209	0.1954396035621450	0.0916684026313754	0.0131478088091973	
+2.9510000000000001	0.0385685830149978	9.8276481358029866	0.0152688568677950	0.1172494351916225	-0.1374770058842273	-0.1613635546115364	
+2.9520000000000000	0.0353507057448699	9.8307400011304864	-0.0039150436289434	-0.3141542144041081	-0.2075421698060546	0.0673542370484238	
+2.9529999999999998	0.0282384748315919	9.8332961504085468	0.0117768339192322	0.1014247722347319	0.3128697934958152	-0.0438407338215991	
+2.9540000000000002	0.0324591723957654	9.8395633797815005	0.0094204432554011	-0.0450068693719078	0.0425984517336076	-0.2043363327262806	
+2.9550000000000001	0.0271807176791176	9.8285687405257622	0.0047546316977320	-0.0709288293469983	0.3754902112070461	0.0327619553693055	
+2.9560000000000000	0.0599059760488771	9.8283960287224037	0.0100117961435910	-0.0082093888697141	0.0247554146014639	-0.0010060292355370	
+2.9569999999999999	0.0312599514547090	9.8282036416638920	0.0006725213151720	0.0048078261756019	0.0462808709322322	0.2942195071849105	
+2.9580000000000002	0.0326092148574884	9.8298835612080531	0.0086919451416394	-0.0248971753304522	-0.0910557036342106	0.2106559937973485	
+2.9590000000000001	0.0332416506669787	9.8177752948247718	0.0130994526198594	0.1158416905996753	0.0197699224259286	0.3228743476850414	
+2.9600000000000000	0.0332186568822777	9.8247139469328566	-0.0022169183855789	-0.0461489738257038	-0.0365186425839762	0.1459908161620847	
+2.9609999999999999	0.0400159619247493	9.8231341604942006	0.0043774938505146	-0.1482982311694396	-0.1744932862251681	-0.1464178322502870	
+2.9620000000000002	0.0192013923056541	9.8308826706567114	0.0199288756501694	0.0514516308432986	0.0486961941859544	0.2312006307483655	
+2.9630000000000001	0.0390306258274394	9.8444025975438763	-0.0128430327468700	0.1048271336070092	0.3466058829961377	0.0398374375675544	
+2.9640000000000000	0.0152831298850116	9.8319988039452131	0.0117791041252937	0.1113695760937402	0.2052717650082801	0.0400455340783540	
+2.9649999999999999	0.0378628665161942	9.8544484713942762	-0.0223027759980743	0.0800656961757858	0.0154274905016005	0.0181308570625588	
+2.9660000000000002	0.0253661612596699	9.8198448955323911	0.0049070091798287	0.4970798165545061	-0.1156724748295364	-0.1310293984966890	
+2.9670000000000001	0.0287128945187589	9.8519477958065114	0.0189852576217424	0.0472066378562453	-0.2304120760411071	0.0658366812378939	
+2.9680000000000000	0.0490333322577648	9.8514768135891337	0.0077881402294998	0.1369197792736187	-0.1049910736577981	0.3008398673052912	
+2.9689999999999999	0.0332678115242166	9.8349227259981085	0.0172945459817372	0.3387156222051126	0.0356758959120354	0.0721615072890432	
+2.9700000000000002	0.0403406720849714	9.8473161806950262	-0.0020290803418625	0.0183931119079442	0.1176334960974993	0.1275942737414555	
+2.9710000000000001	0.0262692923337069	9.8267828037769434	0.0060436280061078	0.0979686517187331	0.0957295720002291	0.2598466456757925	
+2.9720000000000000	0.0293452287234879	9.8290443451124840	0.0103632039727289	0.3070252541567978	-0.0740235095262016	-0.0996894353649117	
+2.9729999999999999	0.0328638367829848	9.8239281220933883	0.0049066508797131	0.0518697405716683	-0.2707152082213738	-0.0425073317192421	
+2.9740000000000002	0.0154562782723425	9.8479075597225361	-0.0067652827131131	0.0582560367497189	0.1455616445233296	0.1697169030370060	
+2.9750000000000001	0.0341926741790142	9.8232642221003381	0.0103978719413136	0.0511695279926055	-0.3166171034126622	0.1872782486282517	
+2.9760000000000000	0.0514157762119190	9.8400297166136852	-0.0085644694828471	0.0432681154712558	0.0780453003585817	0.1000324848586754	
+2.9769999999999999	0.0376496290474363	9.8315320803769044	0.0158559601122498	-0.1093181364020381	0.1682582513430930	0.2730827740943795	
+2.9780000000000002	0.0185002103330090	9.8183038722494409	-0.0082701879526712	0.1971891053559830	0.3372773547099318	0.3545280371838964	
+2.9790000000000001	0.0215996164707237	9.8025524298443987	0.0090033623230280	-0.0032028842421696	0.0431859745877474	0.1392446763915706	
+2.9800000000000000	0.0218866210969233	9.8225996524775230	0.0000545425974379	0.2938701636377410	0.3217994669226817	0.3830790430193075	
+2.9809999999999999	0.0635060716400007	9.8122149509379604	0.0200286496476450	-0.1248193786861691	-0.1584616727380706	0.0048941110862694	
+2.9820000000000002	0.0270242161035420	9.8276312337942677	-0.0044728935062178	0.1462110614814401	0.0456276404173876	0.2429605783722493	
+2.9830000000000001	0.0331154566608986	9.8395050875257919	-0.0153464394156658	0.1300078505173105	-0.1722762020967086	-0.3600370936621145	
+2.9840000000000000	0.0474741366478216	9.8286753532524376	-0.0356881677380951	0.0994921723388179	-0.0344825038406714	0.1846263661832966	
+2.9849999999999999	0.0329363551215720	9.8386042829524030	0.0051211052968005	-0.1132736706501602	0.1023039570110522	0.1723335556001957	
+2.9860000000000002	0.0307498026699362	9.8334725810411605	0.0064953984080690	0.1789045791713706	-0.1257748596750175	0.2199786490029190	
+2.9870000000000001	0.0180808068932169	9.8271939459543898	-0.0065506689477109	0.0762319324696306	-0.0531826865194135	-0.1553070801163283	
+2.9880000000000000	0.0360514983350108	9.8321428754320355	0.0155264575056730	-0.0039963596873521	-0.1496281969710393	0.4294390990416705	
+2.9889999999999999	0.0475172466784297	9.8394208425820633	0.0034266562700004	0.0481721303202089	0.0056904384935943	0.2732709159479565	
+2.9900000000000002	0.0038646867488136	9.8357394813584911	-0.0045408267881082	-0.0231965172438263	-0.2748178480224964	0.0340424515656861	
+2.9910000000000001	0.0415498861635094	9.8217530874862700	0.0164454364452980	0.1025064852850369	0.1983605870320538	0.0521636598102259	
+2.9920000000000000	0.0442471849368303	9.8467776710520347	0.0244989972933635	0.2492221322585338	-0.2192780052691902	0.1544021806037229	
+2.9929999999999999	0.0424665857039592	9.8290532712194985	-0.0049992301900481	0.2046260188527547	-0.1154341068051622	0.1781542798308284	
+2.9940000000000002	0.0392855064834244	9.8544724521924163	0.0232684586284592	0.0443111624906185	0.0099905366976692	-0.0062374580540039	
+2.9950000000000001	0.0108283754879650	9.8379478743387203	-0.0191436360831761	0.0618616927633570	0.1570416150980244	-0.1006791707189953	
+2.9960000000000000	0.0167274646246705	9.8327485663445753	0.0191614824637850	-0.0810147738516973	-0.0413252091129160	0.0875960784319634	
+2.9969999999999999	0.0424983492138475	9.8236621116743486	-0.0028686112119058	-0.2096393018063593	-0.1922661672375776	0.3302532895557299	
+2.9980000000000002	0.0289178600766615	9.8140465474819436	-0.0170686216923647	-0.1890927710608021	0.0725223956658542	0.3943379325940446	
+2.9990000000000001	0.0347896403048730	9.8286571384940231	-0.0070243082615766	0.1127370609110230	-0.0210542188961585	-0.0600573184264809	
+3.0000000000000000	0.0456884186467573	9.8131707128154240	0.0233470976013751	-0.0552404113373066	-0.0802862449919132	-0.2598301498834574	
+3.0009999999999999	0.0192510296944226	9.8250000894485598	0.0012534888428952	0.2063857834052159	-0.1108413049708645	0.0821878498889095	
+3.0020000000000002	0.0363812091547060	9.8457973552771545	-0.0150249431640502	0.0249022326010752	-0.1599704020431568	0.0544766950782158	
+3.0029999999999997	0.0095011606701917	9.8345978718895157	-0.0022272308614201	0.1611937152424785	-3.1870215177898937	0.0872968526710590	
+3.0040000000000000	0.0276371510282090	9.7891183936096571	-0.0137819143381433	-0.0846374621641287	-3.0512781205499913	0.0442414276434796	
+3.0049999999999999	0.0208965660407993	9.8342879075799630	-0.0017071472839227	0.4004386575647562	-2.8403361126032634	0.2265383195853224	
+3.0059999999999998	0.0446968675492318	9.8325997634263818	-0.0105759600765004	0.0912610445698918	-3.0008234031039134	0.0708041879036318	
+3.0069999999999997	0.0333732177217175	9.8168175674483713	-0.0075906232158106	0.0287231070627062	-2.9119177933539957	0.0090434373272899	
+3.0080000000000000	0.0230887399788185	9.8468226152919733	-0.0114986407559258	-0.1812258657083274	-3.1904681158201349	0.2179622765924520	
+3.0089999999999999	0.0217633583797225	9.8005455208360015	0.0051433277630019	0.2914451300317870	-3.3061795258271975	-0.1255119619793841	
+3.0099999999999998	0.0380279046964897	9.8132972617079623	-0.0058907347212330	0.1376663985420595	-2.9791850247959273	0.1830924223653696	
+3.0109999999999997	0.0399727594300522	9.8349891815688935	-0.0150340602762043	-0.2230081209082711	-3.2934590606387970	-0.0871681758086744	
+3.0120000000000000	0.0204275740255840	9.8031376379756470	-0.0386645068101819	0.0927177395682131	-3.4312335608046851	0.1773786133796507	
+3.0129999999999999	0.0281516902537476	9.8208740951985618	-0.0132642481917814	0.1421506106780778	-3.2463477688269156	0.3574129041552196	
+3.0139999999999998	0.0279242756568073	9.8263478448178283	-0.0080225378963097	0.0292649973885013	-3.1009259231516135	0.0274620550747618	
+3.0149999999999997	0.0369529957055617	9.8243888769607324	0.0056335847960309	0.1514095190993844	-3.2094714879585342	-0.1813294565717511	
+3.0160000000000000	0.0023199958052726	9.8098580005149394	-0.0256106289104348	0.2076132515356466	-2.9153823147615001	0.2389528994135284	
+3.0169999999999999	0.0157564122345688	9.8073258681576974	-0.0255900871721960	0.1741177567630783	-3.1443160557951284	-0.0052624395235688	
+3.0179999999999998	0.0338890210423301	9.8145245810843367	0.0013344233164235	-0.1246738274999070	-3.1425420320617681	0.0283606847835655	
+3.0189999999999997	0.0270851692845511	9.8343859123922535	-0.0012315519791143	0.0872759928315392	-3.2301244449852895	0.1179563266379800	
+3.0200000000000000	0.0301000832465378	9.7941498459518197	-0.0077861785733864	0.1970675237830334	-2.9687603504116113	-0.1629178265327221	
+3.0209999999999999	0.0316658580155011	9.8226241036252375	-0.0076837049441859	0.1297443177777017	-3.2060528387109697	-0.0875675738016842	
+3.0219999999999998	0.0272374830070519	9.8302748804816371	-0.0126346793815354	0.0964344195463559	-2.7564985841245799	0.2671088962292134	
+3.0229999999999997	0.0176618750911932	9.8398214321363735	-0.0015996336007543	-0.0245016073620128	-3.4374495450424822	0.0047348234891709	
+3.0240000000000000	0.0339438131501455	9.8122471738251207	-0.0193899837596275	-0.0658467574955192	-3.0894385588583888	0.0821455558783720	
+3.0249999999999999	0.0223354668552222	9.8414538298219547	-0.0022335268342217	-0.0803554682861203	-3.0122571831109157	-0.0479235494683698	
+3.0259999999999998	0.0043798642561321	9.8269989017275314	-0.0381971147360365	-0.0648231177652940	-3.2594598655661584	0.0202131024036981	
+3.0269999999999997	0.0153968106698179	9.8241802840876638	-0.0050637436466535	-0.0255512348650923	-2.9929403378214809	0.3079709038440211	
+3.0280000000000000	0.0301589507725618	9.8438631325140769	-0.0036530654545582	-0.0893379836200684	-3.1108378218139401	0.2854803498520836	
+3.0289999999999999	0.0115159713319539	9.8337031281973459	-0.0193937740333804	-0.2205812061731868	-3.2820627834513276	0.0231168135465582	
+3.0299999999999998	0.0189763156323437	9.8105393785834938	0.0092744102554221	0.0106710566523617	-3.1373540867245975	-0.0857529778848678	
+3.0309999999999997	-0.0022580689090555	9.8321498534414271	0.0043634770049804	0.1008959525195597	-3.3883912576363580	0.0517046170426814	
+3.0320000000000000	0.0299235007806059	9.8250740260420919	0.0050007900676460	-0.1590128449515246	-3.4256123482911103	0.0868499331405455	
+3.0329999999999999	0.0099502713931710	9.8351977199495657	-0.0112353074420741	0.0711620322487966	-3.2076843117635430	-0.0105613190947631	
+3.0339999999999998	0.0121672845129530	9.8175432431842040	-0.0206116374818630	-0.0589062098089474	-3.0992368289685630	0.0868279793362637	
+3.0349999999999997	0.0335531919215482	9.8239556226503506	-0.0139409208061795	0.1036611175447621	-3.3305064316844697	0.1445284199179859	
+3.0360000000000000	0.0401126350959903	9.8131673497235692	-0.0233261887331625	0.1928012520841855	-2.9384614673558000	0.1311970838468052	
+3.0369999999999999	0.0269944614091892	9.8419097845497259	-0.0267749913900166	-0.0144882890500005	-3.1934299681856717	0.0672950188513956	
+3.0379999999999998	0.0138949308599964	9.8238229913718556	-0.0263835683763617	0.1274500664109257	-3.3002356382786999	0.0703435250646505	
+3.0389999999999997	0.0262610917272208	9.8186670864632646	-0.0009365141167244	0.1188385079351619	-3.1429113254830328	0.2566235314838533	
+3.0400000000000000	0.0313308488391612	9.8444279900082901	0.0132066709877030	0.1879563682917417	-2.9619841168065895	0.1787582273242071	
+3.0409999999999999	0.0397393906656692	9.8365707233086148	0.0077314430678011	0.0408343230668440	-2.9306636168052500	0.0032908278982101	
+3.0419999999999998	0.0195950700884305	9.8229829749859512	-0.0075741771407972	-0.1245498017173024	-3.0083571271343859	0.1605417487559253	
+3.0429999999999997	0.0289039086902724	9.8120306180758448	-0.0094811887418385	0.0138291855625977	-3.1213455233468803	0.1870462108314512	
+3.0440000000000000	0.0373314487732650	9.8108548232187918	-0.0072401186209869	-0.0478695754861608	-3.1136439981594664	0.3720488639139791	
+3.0449999999999999	0.0474814389044113	9.8126440275046836	0.0203957755122546	0.0819881423347016	-3.1812517336337014	-0.0133431063651311	
+3.0459999999999998	0.0254392888293950	9.8193797756469099	-0.0086813943525399	-0.2328775964599024	-2.9351839337168593	-0.0330531400398506	
+3.0469999999999997	0.0293446892626091	9.8102335763828030	-0.0031891748063922	0.0828422357263993	-3.2308985866123714	0.1322266964927993	
+3.0480000000000000	0.0524684981782449	9.8075663879331003	-0.0207137534696530	-0.0625347671142478	-3.1157537779322739	-0.2534294105953436	
+3.0489999999999999	0.0194932257341189	9.8226165902754161	-0.0263549409730071	0.1238711484386793	-3.1100076111880455	0.0928989788011875	
+3.0499999999999998	0.0283639640851749	9.8226809133814807	-0.0191138928318179	0.1845453989710006	-3.1828753541573609	0.0068827728184153	
+3.0509999999999997	0.0264935367191945	9.8052097825266404	0.0023642156412051	-0.1457704922990828	-3.2449047510058282	0.2938641734295517	
+3.0520000000000000	-0.0111881080281574	9.8112768251258995	-0.0034555737324295	-0.0512820433831635	-3.3169573341732863	0.0083696892479141	
+3.0529999999999999	0.0307288641079547	9.8268391299450535	-0.0089981726433514	0.0714444338087976	-2.8037159408577068	0.1148480492071898	
+3.0539999999999998	0.0412272130625702	9.8209392735865340	-0.0183238292622371	0.4333875385589838	-3.4113399609037351	-0.0242979571489241	
+3.0549999999999997	0.0236468391989692	9.8279804321386024	-0.0088107378882226	-0.1443297319866810	-3.2958843815032957	0.2695480587707917	
+3.0560000000000000	0.0104823083065929	9.8176780559275834	-0.0183910009736467	0.0063477885070945	-3.3269235220555684	-0.2139581308682454	
+3.0569999999999999	0.0006241071861612	9.7989896639007927	-0.0075821483134966	0.2564948436965774	-3.3187784861737670	0.0111967168553365	
+3.0579999999999998	0.0204516349382867	9.8406322287895129	-0.0112636005673506	0.0319937377738036	-3.3789400469199879	0.1166059043661172	
+3.0589999999999997	0.0244605596795791	9.8240466612817272	-0.0156400926171635	-0.0528461265508675	-3.0759655687265988	0.0907544510215077	
+3.0600000000000001	0.0190991841755329	9.8279161043936369	-0.0110458722170819	0.2405694891640933	-3.0204175401219677	0.2488572862964282	
+3.0609999999999999	0.0256961576263904	9.8345063492307130	0.0006603889470793	-0.0720040198013855	-3.2060548312128541	0.1256643056442013	
+3.0619999999999998	0.0347860325169844	9.8243314058859017	-0.0035422929803984	-0.0262018745482379	-3.0393003432081547	-0.1701713718687254	
+3.0629999999999997	0.0115584322331133	9.8175187331159428	-0.0194957413223997	-0.2982516580665669	-3.1390053953534403	0.0972011097734291	
+3.0639999999999996	0.0280163214076113	9.8268963336004553	0.0006530753264791	0.2907896938894825	-3.4018017478507923	0.2214943226150012	
+3.0649999999999999	0.0240786578216730	9.8259670292557004	-0.0149259946024911	0.1678833557098016	-3.1505217628492521	0.1011141756199976	
+3.0659999999999998	0.0223081170530354	9.8372255005678042	-0.0240091920714154	0.0343273395205587	-3.3431487068387384	0.1009482770562899	
+3.0669999999999997	0.0442553971504899	9.8489320538221534	-0.0048484416014265	0.1124024352364855	-3.4839849984891709	0.0653263809708520	
+3.0679999999999996	0.0233707744477657	9.8207733381003131	-0.0119489919199848	-0.0376380594158820	-3.1646360633337935	0.1602072510402890	
+3.0690000000000000	0.0144966184907385	9.8282726826357951	0.0012673020520805	0.2962465522495589	-3.1604297660914353	0.0233420771920487	
+3.0699999999999998	0.0327674230652735	9.8162997257311790	-0.0178997441126984	-0.0690670573475163	-3.2025843944920553	0.1975657323879406	
+3.0709999999999997	0.0232082602736812	9.8073463615449370	-0.0012703240635609	0.0523716916878812	-2.9787563584480434	0.0905189142416332	
+3.0719999999999996	0.0249217874334519	9.8249942739520755	-0.0077345057236735	0.0159970785820159	-3.0962171703108736	0.1017464721216172	
+3.0730000000000000	0.0429059273934412	9.8194105811557630	-0.0058781583623750	0.1512466855476748	-3.1187998405335438	0.0808478297556264	
+3.0739999999999998	0.0314397226410431	9.8248401831582370	-0.0091544199781795	0.0242359756056371	-3.2748335451935637	0.2812001421013654	
+3.0749999999999997	0.0281863152034225	9.8477145127777614	-0.0029855007614771	0.1190153835260209	-3.1575445899567156	0.0437435625731728	
+3.0759999999999996	0.0211023006996757	9.8119921262017513	-0.0075399284530384	0.0570537594181605	-3.2711076696985359	0.0270618321703558	
+3.0770000000000000	0.0417903424847860	9.8013588582010129	-0.0164862260754596	-0.0206901825005349	-3.1053624561279713	-0.0449601955549642	
+3.0779999999999998	0.0354403133089314	9.8160878046126925	-0.0175628581596429	0.1442868048874743	-3.3258034663380602	-0.0990664417494082	
+3.0789999999999997	0.0255078754121859	9.8219486589343106	-0.0143702143726781	0.0785428538851780	-3.3832497535126200	0.0394681473810103	
+3.0799999999999996	0.0111082118110144	9.8216060388149771	0.0038531524877433	0.1447489781837756	-3.1437582913553248	0.2207118740377200	
+3.0810000000000000	0.0225872081580175	9.8469238478634615	-0.0025170258521671	0.1368914593477537	-3.3312494129441275	0.0639546453882623	
+3.0819999999999999	0.0143796654370672	9.8287076620895242	-0.0039466125376060	0.0732153334808326	-2.8723664286894390	-0.0399391832041855	
+3.0829999999999997	0.0416146407921998	9.8168470652313360	-0.0058477448223434	0.0457202130478992	-3.2934185382558754	-0.1323650860436748	
+3.0839999999999996	-0.0053498878335236	9.8497196612251781	-0.0017702212711852	0.2807356158269030	-3.3909010759950275	-0.0224342902396483	
+3.0850000000000000	0.0089536660084773	9.8351385498766373	0.0014761701233341	0.1966154027904480	-3.0714573883887852	0.2250715961960844	
+3.0859999999999999	0.0237906099399943	9.8315096377279225	-0.0026470576717524	0.1419236273635656	-3.2553069656215952	0.0049518546932751	
+3.0869999999999997	0.0259904522858720	9.8150985878846519	0.0009767800764882	0.1085020159982234	-2.9679562673795861	0.1178068378951417	
+3.0879999999999996	0.0247757057926714	9.8240575157653076	-0.0081986614222160	0.0816109974319583	-3.4522361132320034	0.2283002626320517	
+3.0890000000000000	0.0495134780909632	9.8339535675541718	-0.0226845743328617	-0.1249840786576694	-3.0646039005289971	0.3326296012408285	
+3.0899999999999999	0.0192921134100698	9.8244480053192884	-0.0203507622947369	0.1670766472022365	-2.9640755585070089	0.0696990380153991	
+3.0909999999999997	0.0324334023799650	9.8310112862466781	0.0034870139749345	0.1573470993395172	-3.1888508285324044	0.0689459845196800	
+3.0919999999999996	0.0288839337633243	9.8210510823233559	-0.0014103571677357	0.1727074234965264	-3.3312131482095113	-0.0039565850306937	
+3.0930000000000000	0.0247577087048534	9.8356860143211406	0.0010537880785758	-0.1216455736560945	-3.1584408810791307	-0.0511298500506748	
+3.0939999999999999	0.0193524205158393	9.8111105554456337	-0.0229763904148989	-0.0883436542371795	-3.0989644259216367	0.3788642731582523	
+3.0949999999999998	0.0328258230898061	9.8130017740352429	0.0171680430739509	0.1627950012166195	-3.1285783238061109	0.0944056986351303	
+3.0959999999999996	0.0277778240701387	9.8148599660814941	0.0014365906685882	0.2113409001833237	-3.1435623520467497	-0.1270257626651194	
+3.0970000000000000	-0.0094011008613492	9.8331994208628846	0.0142174829878859	0.0507482336750097	-3.3380574268744452	0.1371533247002543	
+3.0979999999999999	0.0233436477326726	9.8111003707134170	0.0108520780474691	-0.1263142199128910	-3.3629330825472388	0.1858304030602130	
+3.0989999999999998	0.0100100940150890	9.8242145482896390	0.0046808500701346	-0.0259250125821848	-3.2498664288691379	0.0046573921620285	
+3.0999999999999996	0.0221933023420960	9.8146821245742313	-0.0124587546509381	-0.0299911677761821	-3.1891631881919298	0.0961635821241054	
+3.1010000000000000	0.0357805144046487	9.8149724239354885	-0.0031203486643845	0.1216356026570379	-2.8759845652326073	0.0270048404084187	
+3.1019999999999999	0.0415165859121020	9.8290170916720889	0.0124493961057257	-0.1345608962991388	-3.3119958995022678	0.2846347473863018	
+3.1029999999999998	0.0135201997239954	9.8128689968959506	0.0019841056630738	-0.2017622869485095	-2.9669360898390993	0.2170662100588068	
+3.1039999999999996	0.0313900072989115	9.7916944677097977	-0.0123697752100265	-0.2786540065122740	-3.3441393461547642	0.1717599953183597	
+3.1050000000000000	0.0143379976688278	9.8105397530394214	-0.0102211346117174	0.0989869343369928	-3.2011752949440795	0.2323817885299875	
+3.1059999999999999	0.0287467724773420	9.8392867779447375	-0.0000167984651850	0.1305400279168772	-3.0458560183779513	0.2368788965175678	
+3.1069999999999998	0.0194786275968199	9.8365120051214685	0.0217602387926029	0.0647530558786448	-3.2233249581242531	0.1371412130246484	
+3.1079999999999997	0.0428681027588138	9.8313813057189297	0.0197816100597214	-0.0601727372582227	-3.1459891380369331	0.0611047040266206	
+3.1090000000000000	0.0162069161869867	9.8250446288045143	0.0130769936643965	0.0024535120298081	-3.2654108316704531	0.2330906920735225	
+3.1099999999999999	0.0419580418152796	9.8241175949828374	0.0060599906070419	-0.1944371717770083	-3.0115180590400286	-0.0402636531885429	
+3.1109999999999998	0.0144664578557374	9.8516647282452290	0.0013014870958212	0.1727180029192810	-3.1148317829412484	0.2407006673466127	
+3.1119999999999997	0.0388050951138363	9.8114195860020388	0.0023821630386383	0.2632743712905878	-2.9446509615656273	0.2198701924163040	
+3.1130000000000000	0.0255354358981073	9.8318451322358733	0.0006466116685255	0.1536445256843861	-3.0882108857723747	0.2431621861622872	
+3.1139999999999999	0.0441291298507866	9.8323201067510357	-0.0091172272406703	-0.0323980465085651	-3.5335628385378306	0.1352727079922765	
+3.1149999999999998	0.0470670924576294	9.8448097423877030	-0.0081975219664207	0.1039958421647660	-3.0257464003167809	0.0411325614842432	
+3.1159999999999997	0.0127128344084639	9.8371844441139125	0.0120647667787651	0.3707578342750895	-3.2009048937876310	-0.1004410736027248	
+3.1170000000000000	0.0066769416627220	9.8405560185003491	-0.0032413419394453	-0.2399019328292493	-3.1233363719861709	0.2268378906551416	
+3.1179999999999999	0.0164512389226034	9.8204928882907101	0.0020757420642368	-0.0176068904513391	-3.3407416452025611	0.1935680983004027	
+3.1189999999999998	0.0238870074480072	9.8507722625238205	-0.0282583454300289	-0.0676425009299629	-3.2932414577887319	0.2267767586149703	
+3.1199999999999997	0.0283506923175328	9.8277509259113263	0.0098445911936272	0.3102027569702979	-2.9305739868385787	0.2089168917284139	
+3.1210000000000000	0.0264968105457552	9.8164790879962851	0.0044624932874103	0.1400735953322926	-3.1058148897288800	0.1465239760182916	
+3.1219999999999999	0.0324893630032198	9.8190168757874154	0.0083214574441995	-0.0085221681483429	-3.3590103221406959	0.0862262651753169	
+3.1229999999999998	0.0198247229619114	9.8288996270761171	0.0060914288594442	0.0702038591837880	-3.0997310661407145	0.1171904955273829	
+3.1239999999999997	0.0198528976170246	9.8231733491184929	0.0140945543298641	-0.0418823324243756	-3.1445452721853768	0.3797498621152253	
+3.1250000000000000	0.0242787688129047	9.8108088832513403	-0.0108864500008656	0.0283482353071729	-2.9521070533193439	-0.1556260977255745	
+3.1259999999999999	0.0248584270724105	9.8232350657908096	-0.0092779434327900	-0.0038099512669834	-3.0730449032840621	0.0126828615333752	
+3.1269999999999998	0.0287648266963121	9.8138148660513345	-0.0044914527160954	0.1374300326191218	-3.2622906081881249	-0.1154182844268109	
+3.1279999999999997	0.0194898778499956	9.8179897840104466	-0.0132910775958471	0.1859473328667510	-3.1905053990566214	0.0496017036170447	
+3.1290000000000000	0.0282263059250670	9.8218751834866289	0.0165845836092144	0.3655608861160080	-3.1736655451607971	0.1287974018787378	
+3.1299999999999999	0.0296062384616898	9.8122610741742751	0.0016245871762905	-0.0222496819810359	-3.3952853248219106	-0.0121510493709382	
+3.1309999999999998	0.0223532286102443	9.8103013601177338	-0.0054605464782711	-0.1920645915840791	-3.3924237588004367	-0.3431296647997185	
+3.1319999999999997	0.0246651764949307	9.8231855640598216	-0.0082529676924535	0.0993714629500371	-3.3462380737817923	0.0248830638901053	
+3.1330000000000000	0.0227373534537293	9.8136066902389132	0.0062027088611012	-0.1884628319719954	-3.1595704713234496	-0.0376747580706496	
+3.1339999999999999	0.0142419172275171	9.8219351849307088	0.0066728716367222	-0.0871983975403276	-3.2610873068627888	0.4299472367317274	
+3.1349999999999998	0.0339556252731379	9.8169064834815529	0.0103317946784261	-0.0604665789598467	-3.0848580763006055	0.0688629549458551	
+3.1359999999999997	0.0111843643424914	9.8305346369299436	-0.0129794689891388	-0.0335570440025753	-3.2393902971565298	0.0790701119481898	
+3.1370000000000000	0.0125511639256989	9.8154734080105186	-0.0306488864694328	0.1667238278121629	-2.9584646104145729	0.0580393304858835	
+3.1379999999999999	0.0213121673283509	9.8053750298373767	0.0076376386571300	0.2892912521167310	-3.3159697019887542	-0.0656333587862455	
+3.1389999999999998	0.0310683700354727	9.8186155954283070	-0.0034349674825958	0.1187535379876182	-3.2797823302162921	0.1290105875264888	
+3.1399999999999997	0.0218857561928949	9.8081848338787889	0.0099587136938452	-0.0424248724333683	-3.1709076324860401	0.0405560372715930	
+3.1410000000000000	0.0222478345822179	9.8120403374560183	-0.0071844239218177	-0.2105215268078677	-3.0153421169522323	-0.0274878154594504	
+3.1419999999999999	0.0018329999161621	9.8160764256281166	-0.0032301784898933	-0.0386842670248091	-2.8346358337096249	-0.0812084503778491	
+3.1429999999999998	0.0282463836821227	9.8256026071268767	0.0055638970926529	0.2218632441702958	-2.8326148934214075	-0.0000504999530117	
+3.1439999999999997	0.0440006332207987	9.8293040009790591	-0.0011450713798982	0.0625030052911263	-2.9140572105620675	0.0580247837878301	
+3.1450000000000000	0.0134992071440298	9.8364704519304631	-0.0008376234216232	0.1510420371531338	-3.0727524764570688	-0.0983260336968196	
+3.1459999999999999	0.0327996549196893	9.8397203596978962	0.0203452059966821	-0.1238613167014246	-3.3792862717467296	0.3114252257104963	
+3.1469999999999998	0.0259028176793570	9.8254654836325077	0.0048110610428711	0.2880094841521322	-2.9309032693100154	0.3385965701388495	
+3.1479999999999997	0.0280139330198875	9.8184365970323846	-0.0190836274365906	0.1184893784770976	-3.2253740048841903	-0.1971775446861017	
+3.1490000000000000	0.0202769306629910	9.8159338824179212	-0.0049576645380200	-0.0226043912592732	-3.3613589397239139	-0.0527740586483012	
+3.1499999999999999	0.0268835741509647	9.8369863752418158	0.0082648774286101	0.0060625654013136	-3.2374656641080781	0.2281503333953752	
+3.1509999999999998	0.0374776222786246	9.8394299171510422	-0.0015676605739409	0.0623762877746978	-3.1415749166410065	0.1160896846597694	
+3.1519999999999997	0.0163750046405041	9.8199040555576165	0.0137105593360149	-0.3536022371902918	-3.1446627619737608	0.3948719743371547	
+3.1530000000000000	0.0115471231208120	9.8046264145824917	0.0144439277270241	-0.2807627959173691	-3.3303056101807824	0.1945821758256454	
+3.1539999999999999	0.0129658790056126	9.8135499681398191	-0.0030803596407641	0.1426772344662964	-3.1042958183617935	0.0301975503566267	
+3.1549999999999998	-0.0052035075726637	9.8344955221615553	-0.0038109380569712	0.0225538152367528	-3.4993432212017215	0.0785068532869967	
+3.1559999999999997	0.0223929806994363	9.8173555595491990	0.0166924812060165	0.0091504657420410	-3.2188281537198846	0.0416816810389289	
+3.1570000000000000	0.0244921535618738	9.8238479403286849	0.0139238074721668	0.0884328099686676	-3.3139526763146887	-0.0159652482376760	
+3.1579999999999999	0.0249646073626512	9.8062555926592072	0.0062447806109810	-0.1719725845787293	-3.1673575004154046	0.2474378486480333	
+3.1589999999999998	0.0291772120264047	9.8270708509191227	0.0053505660389424	-0.5018731650247182	-2.9934140632451540	0.1873799856987874	
+3.1599999999999997	0.0200725028925092	9.8292373646913624	-0.0243207467204630	-0.1615499659469581	-3.2717601678676189	0.1141896952351315	
+3.1610000000000000	0.0422084756325535	9.8155467571012132	-0.0036470691568859	-0.0195082537988350	-2.9658540038169958	0.0958782902418613	
+3.1619999999999999	0.0179389538399258	9.8094787282946090	-0.0404217137625434	-0.1475527032623882	-3.1236875307501553	0.0131947243121077	
+3.1629999999999998	0.0202913197518162	9.8111940045433350	-0.0114399188840713	0.0554657147396949	-2.9562774876472191	0.3364019536189370	
+3.1639999999999997	0.0351440914983077	9.8293329412498984	-0.0050926675712586	0.1425975528413950	-3.3016769103442480	0.1142510568023418	
+3.1650000000000000	0.0405358470797626	9.8220239521243844	0.0177117212768018	0.0398971222495148	-3.3791237076180614	0.1901045646778237	
+3.1659999999999999	0.0311730661349179	9.8402816146568810	-0.0001447635743048	0.0105418082883851	-3.1449887555937237	0.3039369415588558	
+3.1669999999999998	0.0233131909543180	9.8117138087951705	-0.0217136740702680	-0.1897239829480936	-3.2068332205877246	0.0370560699659354	
+3.1679999999999997	0.0210620318688494	9.8256019401286085	0.0163164250957129	0.2565443759859757	-3.1573404923675543	-0.1191705338524065	
+3.1690000000000000	0.0382617040785908	9.8393086911729917	0.0103710644494300	0.0342800738595599	-3.2253097953724521	0.1333743047490438	
+3.1699999999999999	0.0026473879927816	9.8081452222028922	0.0107990127331300	0.3365270688061290	-3.2140946601230196	-0.0570264086485393	
+3.1709999999999998	0.0171419888660126	9.8072301712133783	0.0098464615905570	-0.0803237934046187	-3.1676248615292968	0.2458185353030580	
+3.1719999999999997	0.0379052549262586	9.8272837778801563	-0.0056968230826843	-0.1040498076352873	-3.2343081442476374	-0.0703260488931946	
+3.1730000000000000	0.0287081724739768	9.8202856635355449	0.0101041239800318	0.0862594605523349	-3.3188537612737083	-0.1841296629239880	
+3.1739999999999999	0.0276017791310425	9.8241612019490105	0.0103749910905058	-0.0412309091236918	-3.3897887259155222	-0.1443184898116625	
+3.1749999999999998	0.0392493153569554	9.8251548825076345	0.0127663052151166	-0.1367545445931018	-3.1098770195993306	-0.1552132651928692	
+3.1759999999999997	0.0310504255522743	9.8380838130382084	0.0034891605641688	-0.0360708618889672	-3.1372120363413609	-0.0040545461918472	
+3.1770000000000000	0.0093357841808819	9.8350326549052074	-0.0022168216549762	0.1431154277381467	-3.2805433430937025	0.0422840885135881	
+3.1779999999999999	0.0318021254975581	9.8186465965398764	-0.0196134947915928	0.0101502417695446	-3.1858600794856087	0.0673042345928131	
+3.1789999999999998	0.0063536093112665	9.8033211160172939	-0.0179183134751299	0.0741315288272884	-3.3661505294634448	0.2442934697847714	
+3.1799999999999997	0.0471792336725103	9.8377491894107170	0.0205075833867967	0.1863513715419885	-3.1481893815449915	0.0155764874439999	
+3.1810000000000000	0.0260545402637440	9.8215920684014915	0.0143991973808026	-0.0622874718493630	-3.0372041646876076	-0.0794082538367398	
+3.1819999999999999	0.0208535307078070	9.8074511752504154	0.0103517077028980	0.0018474785488287	-3.2417438133171652	0.2103726483078734	
+3.1829999999999998	0.0214631751102266	9.8314023069329863	0.0031236748600741	0.0646858848310092	-3.2530804280582299	0.2650612211114262	
+3.1839999999999997	0.0231994949976453	9.8193789695414715	-0.0009401529194051	0.0719394032993401	-3.0423215511806339	0.0146857579881675	
+3.1850000000000001	0.0582077667507108	9.8232160112330469	0.0093688208765036	-0.1383307437123744	-3.2987915775601162	-0.0127167997994675	
+3.1859999999999999	0.0190120145802349	9.8235632941348108	0.0098963862371326	0.1646430005781846	-3.1572916310221983	0.0074462584800897	
+3.1869999999999998	0.0263838417311007	9.8368865020523177	-0.0015136473911389	-0.1698508695772679	-3.3923973092733735	0.0703857181812003	
+3.1879999999999997	0.0439610123246971	9.8143201204406054	0.0014112312302066	0.2933279358543155	-3.3405755682338976	-0.1681684336381257	
+3.1890000000000001	0.0188572492100854	9.8282495149524483	0.0037610533498568	-0.0477859525966431	-3.1078371582524840	0.1301163660404830	
+3.1899999999999999	0.0326752620992580	9.8422656314049082	0.0231994405707740	-0.1327519828135348	-3.1651784265840037	0.1941520038780144	
+3.1909999999999998	0.0374618041689061	9.8326046375991503	-0.0035096172111115	-0.1394632612700449	-2.9568213747517005	0.0018642702450160	
+3.1919999999999997	0.0212914203856435	9.8209560694687230	-0.0033108654650514	-0.0007534338634470	-3.2781806290231188	0.0383908535181943	
+3.1929999999999996	0.0523093076525425	9.8221153389031972	0.0190246525882514	-0.1281543186946447	-3.1976183136180367	0.0327065179374246	
+3.1940000000000000	0.0364087115575727	9.8232336790771306	0.0131625233656586	0.0348258619995409	-2.9227312638626031	-0.1216327188535025	
+3.1949999999999998	0.0259486016283573	9.8232474780652872	0.0098220746460074	0.1131906094201064	-3.0182389865407910	0.0177409319968201	
+3.1959999999999997	0.0108310664161640	9.8529933647401791	0.0056653054723448	0.0609158013462407	-3.4750237615383370	-0.0511570973639117	
+3.1969999999999996	0.0520541826953767	9.8498606688062473	-0.0026577067827257	0.0676747175462872	-3.0315739692766805	0.1313629096793712	
+3.1980000000000000	-0.0052499261913354	9.8267280528084306	0.0002095537680056	0.0193177600546521	-3.2851181511736245	0.0451008610221277	
+3.1989999999999998	0.0291877502872814	9.8215004784448698	0.0080183051816636	0.0969521145784629	-3.1137298929282533	0.3285587949534819	
+3.1999999999999997	0.0231389923483105	9.8120741408790426	0.0057998925777007	0.0639432547228947	-3.2091785211600916	-0.0349779030959275	
+3.2009999999999996	0.0287244287061868	9.8423067817649166	0.0078776681915332	0.0298563184008080	-2.9764419519135537	-0.1195431855106579	
+3.2020000000000000	0.0222365371257437	9.8124758720810430	-0.0106076866081520	0.2069028786785790	-3.3981731306241687	0.2767460763133561	
+3.2029999999999998	0.0370895769512920	9.8192905184557180	0.0184661038520459	-0.0015102324570981	-3.0647670641257347	-0.0120945278981895	
+3.2039999999999997	0.0380783019645725	9.8204646081132125	0.0054987858808687	-0.0631685653748240	-3.0894182828258443	-0.0307121908004628	
+3.2049999999999996	0.0382195326946341	9.8191094007661004	0.0250200744222342	-0.0287646227343458	-3.4094834241261154	-0.2218567039261129	
+3.2060000000000000	0.0398932150909846	9.8165383189068809	-0.0090507669446616	0.0604840341782098	-3.1563632767219691	-0.0744059795309989	
+3.2069999999999999	0.0156782084913286	9.8081464506730800	0.0005830071113574	0.1994770823371868	-3.3124692025405449	0.0745874090813248	
+3.2079999999999997	0.0301080293444332	9.8168679713819351	0.0240106986899351	0.0013228927469165	-3.5092194361821551	-0.1706596523199546	
+3.2089999999999996	0.0336133888669829	9.8243905691680720	0.0029741009177024	0.1898136082404415	-3.1606648829089803	0.2850341179521076	
+3.2100000000000000	0.0150943779879175	9.8244495810045382	0.0121601355431235	-0.0020950665215043	-3.0168021939855616	0.2985285139640237	
+3.2109999999999999	0.0215803866580550	9.8165888329079962	0.0117457678748768	0.0338613049059901	-3.1850045697343941	0.0585724221700783	
+3.2119999999999997	0.0171549874718821	9.8348076043522603	0.0035361716688926	0.1810468601239559	-3.3502788396446026	0.1097510083717593	
+3.2129999999999996	0.0285904710669195	9.8078307848186164	-0.0140657750312749	0.2155711246888937	-3.2267981641725640	0.3011562675434508	
+3.2140000000000000	0.0475247673111788	9.8216042562073547	0.0088967951227305	0.0370650887885623	-3.1466102334997781	0.0386081287276619	
+3.2149999999999999	0.0206071942061691	9.7956729521136872	0.0074172344388048	0.2007200654040746	-2.9553196502043990	0.0392995619406374	
+3.2159999999999997	0.0483965540461243	9.8121629735074460	-0.0367143334608988	0.0442467617732835	-2.9966232244873536	0.0159853733601418	
+3.2169999999999996	0.0311734317160615	9.8190284048822285	-0.0069948610461230	0.1616408031038211	-3.3525620773370290	0.1086036662093851	
+3.2180000000000000	0.0424515373855368	9.8273599207058453	0.0163236311576869	0.1656995935988410	-3.0287757803632704	-0.0501273045763779	
+3.2189999999999999	0.0226191677223028	9.8411019851819894	0.0098707990500771	0.2030536838100403	-2.9481894416742591	0.2000036925738205	
+3.2199999999999998	0.0133094120581042	9.8173719187006725	-0.0253873450544234	0.1099751290393743	-3.0674823672204732	-0.1116789969489089	
+3.2209999999999996	0.0482108367787660	9.8172624192161173	0.0043298113209577	0.0183110800770363	-2.9522683218486012	0.2493245893723407	
+3.2220000000000000	0.0396104228475220	9.8384429643334723	0.0343720505475041	0.2136956726202509	-2.9378657491710252	-0.1014986867462558	
+3.2229999999999999	0.0218115428600271	9.8207379750205614	0.0033832777387175	-0.0915955436747312	-2.9932371659885746	-0.0991917397586272	
+3.2239999999999998	0.0249872432969403	9.8144993373275753	0.0062258868148218	0.0811303125586902	-3.2939618910510871	-0.0781899677144593	
+3.2249999999999996	0.0279120135073113	9.8231984453041061	-0.0059827490001280	-0.1362120551830622	-3.2252882548341484	0.1732232730877866	
+3.2260000000000000	0.0369005201673958	9.8313746778123559	0.0034997282328680	0.0799838450684859	-3.0763070999918503	-0.0164102861915840	
+3.2269999999999999	0.0364319474058258	9.8170624004352085	0.0051392250975912	-0.2240523030412030	-3.1808092295540105	-0.0957800785046310	
+3.2279999999999998	0.0274507646779047	9.8119103719888976	0.0077888690417983	-0.1053972379909631	-3.1651815036113420	-0.0728270496035138	
+3.2289999999999996	0.0383015557572136	9.8194519563928573	0.0091823130447384	0.1852763679447383	-3.2924194733110927	0.2134250520812853	
+3.2300000000000000	0.0343963032431188	9.8316495100985133	0.0024207024183095	0.0988683520252449	-3.0814915223055013	0.0877441889599262	
+3.2309999999999999	0.0617372419083672	9.8268084690251225	0.0012435527940256	0.0415408895327172	-3.2522871185818323	0.2080683781881647	
+3.2319999999999998	0.0322521387891453	9.8373552178601713	0.0315803660940259	0.0942169483429195	-2.9828766306708197	0.1941554337164534	
+3.2329999999999997	0.0361962912269800	9.8138763060683409	0.0196366170931007	0.1311146114533279	-3.0542428517844344	0.0466632963437417	
+3.2340000000000000	0.0199745014179360	9.8176894502680536	0.0390281187188949	0.0966912315433338	-3.0204094312736474	-0.0483080611557571	
+3.2349999999999999	0.0566132485857901	9.8210173175350679	0.0211575365259520	0.0973642245998972	-3.1532105915378503	-0.0704366498123774	
+3.2359999999999998	0.0375695330186648	9.8248377397284621	-0.0002194404747699	0.1180679850447218	-3.1568755152335259	-0.0025134426897781	
+3.2369999999999997	0.0309241972217609	9.8133193070402189	-0.0026641525376088	0.1686352605413599	-3.2190556090268183	0.0344694182797434	
+3.2380000000000000	0.0363230451336580	9.8185608652001939	0.0307830594501440	0.3742412274115505	-3.2771107631655898	0.1149498012518121	
+3.2389999999999999	0.0292790081858672	9.8203808900172103	0.0261036782906735	-0.0611628108433593	-3.0501090166792637	0.3365348786081683	
+3.2399999999999998	0.0413289059728012	9.8263897383494321	0.0080285383257838	-0.0010997856750937	-3.1271707029200386	-0.1304779912091649	
+3.2409999999999997	0.0278100956878855	9.8087213354823621	0.0252727631488119	0.1470226094798286	-3.1756982742437820	0.1437203699233673	
+3.2420000000000000	0.0382656893693310	9.8230664965522152	0.0210606378917338	0.1215419735642757	-3.1200979800825501	0.0203209707163205	
+3.2429999999999999	0.0377691120970074	9.8052542890180572	0.0049665499218180	0.1606618194141970	-3.3586370559490235	-0.1590204879074110	
+3.2439999999999998	0.0339648879154906	9.8145001426112444	0.0266343401450105	-0.0777191364216884	-3.1083137773544212	0.1355875550499920	
+3.2449999999999997	0.0390412377338934	9.8080209573113262	0.0081485913371426	0.0171603209098009	-3.1894040768210044	-0.1120026405870077	
+3.2460000000000000	0.0466378810568584	9.8212838756153413	0.0127389238622474	0.2604110216597098	-3.1112575011388910	0.1471413107549358	
+3.2469999999999999	0.0305535320582543	9.8318449241510244	0.0258591992049799	-0.0235920875074725	-3.2551081342445078	0.0681898083088726	
+3.2479999999999998	0.0319602166170821	9.8163300145750405	-0.0115468383900972	0.1407386803570853	-3.1752237195951025	0.1085565816300173	
+3.2489999999999997	0.0414704801709563	9.8204344173486913	-0.0292364307626317	-0.0596369279580329	-3.2176393474577143	0.1465191849954634	
+3.2500000000000000	0.0174271146356728	9.8290623696302983	-0.0096329426234492	0.0637196593075903	-3.2693491411279325	0.1259312009493163	
+3.2509999999999999	0.0135564970558047	9.8154306127608688	0.0050933445592505	0.1996447495536094	-2.9449779792234470	0.3018261473441761	
+3.2519999999999998	0.0360535323108494	9.8115967898395571	0.0124168939399064	0.0845448518124043	-3.5178214448742011	-0.0828407483501641	
+3.2529999999999997	0.0130376961965430	9.8068633559954694	0.0190310284472461	0.0541937704181894	-3.2337322987805202	-0.0421842700500154	
+3.2540000000000000	0.0421742964389486	9.7974957027946292	0.0244190510971351	0.0678507190004512	-3.1971219054934021	-0.1888708517239951	
+3.2549999999999999	0.0347366582639780	9.8327880804676209	-0.0070754668836904	0.4728699290661982	-3.1131389740910436	-0.0819790635723069	
+3.2559999999999998	0.0168623576547560	9.8304318704657412	0.0341984998913598	-0.1883378008464396	-3.1625388692338725	0.1417465196045827	
+3.2569999999999997	0.0167063197106098	9.8103256035232498	0.0154924445009277	-0.1889782936397932	-3.0601436972971547	0.0368275101770142	
+3.2580000000000000	0.0324538722218406	9.8424869208362651	0.0213906822213115	-0.0442499603538283	-3.0625444559411776	-0.1136950383168110	
+3.2589999999999999	0.0225914958402048	9.8221026049338800	0.0140151085327091	-0.2075350978974930	-2.9906907849355746	-0.0525480353420567	
+3.2599999999999998	0.0312010390955259	9.8139110446317392	-0.0069586409698849	0.1078573273884098	-2.9609572670103712	0.1602246403736117	
+3.2609999999999997	0.0237589444876295	9.8240353980081707	0.0144927554543865	0.1079060303743359	-3.1574316456692793	0.1835807357481944	
+3.2620000000000000	0.0278199778621860	9.8265981892222651	0.0113212250818347	-0.0955820908339623	-3.4367642739099860	-0.0094040357333659	
+3.2629999999999999	0.0244902820313439	9.8267853914579089	-0.0173208410065760	-0.3089630676633862	-2.8898810351511615	0.0455447155697876	
+3.2639999999999998	0.0222765290023549	9.8044303040220946	0.0071018005528835	0.1118959162823364	-3.3401072571822579	-0.2863024829796532	
+3.2649999999999997	0.0354929368187215	9.8139063866533167	0.0031036135615840	0.1152199573904717	-2.9969892109943355	0.0764045416240235	
+3.2660000000000000	0.0239522673960087	9.8145260940236874	0.0202420174154423	0.0846690307612681	-3.2020186860952999	0.2741425970686810	
+3.2669999999999999	0.0309094601045198	9.8134159404485271	-0.0015852631172766	0.2553053496722049	-3.1163931934941789	0.1912209391980303	
+3.2679999999999998	0.0469239892304011	9.8139731030577764	0.0173998890206121	0.0283558462998302	-3.3185749942059837	0.0145383329085343	
+3.2689999999999997	0.0156765009722546	9.8005894028166054	0.0243615315683760	0.1874485232688677	-3.2338032482099366	0.1541083850740279	
+3.2700000000000000	0.0478573354280878	9.8330156546691736	0.0082917398790973	0.0794382423739355	-3.3919884760088621	0.1134831779064422	
+3.2709999999999999	0.0549164211138070	9.8256316174205676	0.0014056023053868	0.1567808425790919	-3.3350728697487915	0.1647602668586191	
+3.2719999999999998	0.0514421292942782	9.8108421064838218	0.0012107052852316	0.1256217264620796	-3.0639223705828345	0.0368139807557527	
+3.2729999999999997	0.0249594004157790	9.8178466174398036	0.0140205825011121	-0.0418532221622673	-3.3963949775674496	0.2463836203856572	
+3.2740000000000000	0.0423654035073992	9.8290544297169156	-0.0153673179451100	-0.0147863389478516	-3.1510336399805134	-0.1955540708904374	
+3.2749999999999999	0.0521484061066751	9.8175981717125715	0.0144175986851030	0.0902790316183536	-3.0509347631446162	0.2638983901300962	
+3.2759999999999998	0.0334254665793742	9.8477870372259044	0.0077986338354470	-0.0499925677230893	-3.4052923218368445	0.2248734036505640	
+3.2769999999999997	0.0348792100195151	9.8521568114555560	0.0348244059895650	0.4527745631238647	-3.2476343836554671	0.0687196000309100	
+3.2780000000000000	0.0358023970557959	9.8272150929650479	0.0130978526995842	-0.0196583157159343	-3.0060633344503795	-0.0297491925692668	
+3.2789999999999999	0.0284633865157617	9.8252007699873456	0.0093709923781246	0.2177013143040467	-3.1593287676030055	0.2288884974094315	
+3.2799999999999998	0.0344259981211019	9.8269845819837709	0.0060828774050689	-0.1521950963325557	-3.2484396389044190	-0.0649629094334147	
+3.2809999999999997	0.0329136634672153	9.8320393645943192	0.0090484848112841	0.0252607679822806	-3.2191547464413977	0.1344732127339607	
+3.2820000000000000	0.0161990798551146	9.7995052295228504	0.0032878531886892	-0.2028537434776955	-3.2388629607375679	0.2044713281249128	
+3.2829999999999999	0.0378570824451432	9.8235181427459430	0.0225189241987186	-0.0859374398925122	-3.1294151635743668	0.0060830702850309	
+3.2839999999999998	0.0439231253118012	9.8156732714284054	0.0063999482489949	0.2697650224119040	-3.2383416636773452	-0.1035633871093809	
+3.2849999999999997	0.0088661442800051	9.8240399087796018	0.0104420643642357	-0.0951066768926381	-3.3295352595375483	-0.0612027171116250	
+3.2860000000000000	0.0270502002187955	9.8123001923576041	-0.0114412437143115	-0.1116276831988720	-3.1345880786647098	0.0872397609055603	
+3.2869999999999999	0.0494565541012622	9.8038546131645941	0.0021783759737558	-0.0034725876738626	-3.0919922695605049	0.0571428537406869	
+3.2879999999999998	0.0545940494464849	9.8170270147897014	-0.0043225065734567	-0.0717423036971468	-3.1166743011363138	0.2180930697367843	
+3.2889999999999997	0.0251510680949465	9.8219447452934006	0.0144849422965065	-0.0541401475129630	-3.0137122422131362	-0.0851286931269106	
+3.2900000000000000	0.0406514063914591	9.8216394879548545	0.0183157895736639	0.0439180049074322	-3.3426494505002218	-0.0224116000495143	
+3.2909999999999999	0.0617604403833047	9.8160373047473275	0.0037745459458476	-0.0043146158047431	-3.0024798969453359	0.1880152316632817	
+3.2919999999999998	0.0316900481030202	9.8266410742385641	0.0013902843978163	-0.3597174106013141	-3.0570437390411946	0.2929843680317208	
+3.2929999999999997	0.0074865634073894	9.8135608090064572	0.0232748499828725	0.1211191867935780	-3.0617560594212554	-0.0056413554835371	
+3.2940000000000000	0.0509508245887685	9.7995091432626396	0.0025096916759213	-0.0365935664450289	-2.9496936633049531	0.2912889589722829	
+3.2949999999999999	0.0358722380229474	9.8221407115378554	0.0226021426096567	0.0442310509771484	-3.2954960053064108	-0.0613310553591793	
+3.2959999999999998	0.0334773880245645	9.8101301984301887	0.0115655513993808	-0.1170146093176568	-2.9350298911288162	-0.0034856200166342	
+3.2969999999999997	0.0510623833180054	9.8458254155926923	0.0189671494452623	0.2316260148636526	-3.2869696918734057	0.3268684729930618	
+3.2980000000000000	0.0463444189496573	9.8361778413712049	0.0000400633592522	0.0270583268350698	-3.3177748206531437	-0.1279669454689845	
+3.2989999999999999	0.0434944648888399	9.8288355464698167	0.0145741532420835	0.0593108394084073	-3.1270555828787154	0.0445195741790825	
+3.2999999999999998	0.0368318517216055	9.8149469152746871	0.0044737615424601	0.0344469909758380	-3.1974413591383675	0.1346077364529630	
+3.3009999999999997	0.0357861352508223	9.8283918123327645	0.0305663844791073	-0.2136365826526956	-3.1602274363037886	-0.2428217704159212	
+3.3020000000000000	0.0618024810118581	9.8235845889671189	0.0196128358945110	0.0694902712082059	-3.1246321927753642	0.0650552100724138	
+3.3029999999999999	0.0383432568711946	9.8184875246256791	0.0234500224598844	0.1656621721007638	-3.3773259822037680	0.0886849781427580	
+3.3039999999999998	0.0421648945956099	9.8225557184922412	0.0152304693968578	0.3201242855846199	-3.0773323100406533	0.2287665584371916	
+3.3049999999999997	0.0329556503434517	9.8106286743261197	-0.0011124218736588	0.0509667730830969	-2.9533011223387255	0.1258125385357283	
+3.3060000000000000	0.0444536658235462	9.8342295126304968	0.0078472545549834	0.2989813739724074	-2.9782895568419661	0.1261129059647039	
+3.3069999999999999	0.0429867873977519	9.8448581445738075	0.0162578576255928	0.1055226222576999	-3.4608365625770872	0.2431873357541346	
+3.3079999999999998	0.0568246068078773	9.8082803561665202	0.0152519713522842	0.0503854774746436	-3.2040936201682442	0.1781949919071876	
+3.3089999999999997	0.0570133857827528	9.8356339570721687	-0.0017044501937115	-0.0122542957234495	-3.4700122030984399	-0.1193634163989352	
+3.3100000000000001	0.0378429161233596	9.8235882402486077	0.0067737056748336	0.2034638088290786	-3.0486072123526458	0.0322599274089262	
+3.3109999999999999	0.0304954482990779	9.8192241864256715	-0.0037483061024607	0.0327736692812753	-3.3728792065809912	0.1448187333508542	
+3.3119999999999998	0.0273761835611212	9.8012916900397045	0.0088050372051963	-0.1568293043964598	-3.2753175331941864	0.0768102289652277	
+3.3129999999999997	0.0351407631526738	9.8181954404527261	0.0059768807875960	-0.0739096357181240	-3.2825114143826406	0.0936095900289400	
+3.3140000000000001	0.0485965739222239	9.8094159152584322	0.0201288873281162	0.0129727398585600	-2.9291887634465095	0.0771209705419772	
+3.3149999999999999	0.0266737875415812	9.8369950434916582	0.0082030292540586	0.0167938147567047	-3.1331655049276921	0.2125108231760989	
+3.3159999999999998	0.0440513160811418	9.8187698475351066	0.0115106701047654	-0.1842308434576750	-3.1722101385138215	0.1346739332161128	
+3.3169999999999997	0.0252063633972900	9.8297350582199474	0.0131969617411016	0.1317669395363112	-3.1659827504227542	0.3886054906307892	
+3.3179999999999996	0.0551077189511470	9.8383051115869193	0.0271136480684989	0.2977745073478184	-3.0731513029352233	0.1417800110222859	
+3.3190000000000000	0.0415828850218709	9.8097516597697361	0.0173706423048824	0.1955701457648153	-2.9177864918773753	0.1436225053902501	
+3.3199999999999998	0.0464439705292747	9.8065722763150198	0.0018478156772642	-0.2008875496996024	-3.3316328884299118	0.1438457002099151	
+3.3209999999999997	0.0477418831755817	9.8031442132122262	0.0105894265505374	0.0454971220948363	-3.1543273826536478	0.3618126270315396	
+3.3219999999999996	0.0330939368074710	9.8180109952186285	0.0205073852037433	-0.0689367115816096	-3.1899544971021419	0.2723391464340594	
+3.3230000000000000	0.0557459204473152	9.8467632072431730	0.0076748031344375	0.1660823549635681	-3.0840773015880587	0.2283098388294836	
+3.3239999999999998	0.0348111056058757	9.8350586999332723	-0.0046389029583091	-0.0157381697365240	-3.3229939536715341	0.1280060812410737	
+3.3249999999999997	0.0417489091349713	9.8201660375213908	0.0300705302540863	-0.0205613506311675	-3.3367359384633763	0.2882588012858474	
+3.3259999999999996	0.0381387351309401	9.8255998472348978	0.0159337833353728	-0.2645453677086022	-3.1419160284906242	0.0616872300032545	
+3.3270000000000000	0.0238369779496536	9.8175678720326278	0.0161505196392399	-0.1048569099785364	-3.1051602721662497	0.0521787452652069	
+3.3279999999999998	0.0359657536625018	9.8295794389840978	-0.0007944368419197	0.0163634462891149	-3.2520762960068352	0.0084858283617310	
+3.3289999999999997	0.0564537866056112	9.8451025386046904	0.0255053859414482	0.1742856973928569	-3.2295597214490139	0.1275655021856089	
+3.3299999999999996	0.0397909130642100	9.8085829875449608	0.0075698719021571	0.2007539400945893	-3.4084013607319474	0.1006143575257678	
+3.3310000000000000	0.0283447392961017	9.8187914124490590	0.0128228751972033	-0.0001827516293033	-3.3962391094825941	0.0915174851757556	
+3.3319999999999999	0.0363323886619271	9.8250933672461560	-0.0111230058009421	-0.1772012840660587	-2.8324862358469511	-0.1519991532307316	
+3.3329999999999997	0.0416674456478690	9.8152511063871692	0.0264129688820062	-0.2819664689587412	-3.2287782334356749	0.4010027985811699	
+3.3339999999999996	0.0437469431343897	9.8492040434289230	0.0082978788147232	-0.1179848375689365	-3.0062302584816680	-0.1816282579349836	
+3.3350000000000000	0.0498408727808397	9.8204759778035768	0.0355670597246997	-0.0500389756802449	-3.1272936595795415	0.1506648739572589	
+3.3359999999999999	0.0605825760365250	9.8278010653766650	0.0080896015624576	0.3318454107177973	-2.8648016420106206	0.0641714360685662	
+3.3369999999999997	0.0140661345091171	9.8322608604732071	0.0408882655399037	0.3325598812874451	-3.0785166425126826	-0.0382057260739978	
+3.3379999999999996	0.0086737382001790	9.8165870385961949	0.0062625424677717	0.0518013110862110	-3.2463875993554323	0.3242142637423823	
+3.3390000000000000	0.0127111313715003	9.8126675247580835	0.0336193590031650	0.1605492831612797	-2.9980543266121877	-0.0959417318642377	
+3.3399999999999999	0.0430329532327782	9.8020457265025343	0.0216711213083843	-0.0108189984975557	-3.2591656032071032	-0.0896286243210543	
+3.3409999999999997	0.0394018091958247	9.8198507833235045	0.0156355129882920	0.1092389744469974	-3.1877923788164964	0.3851132436499982	
+3.3419999999999996	0.0264764643917442	9.8283625158529926	0.0219775594684666	-0.2151236369993595	-3.3972510796369004	0.1233744131732503	
+3.3430000000000000	0.0428990310584915	9.8228445068101919	0.0089767487018222	0.2121237900715815	-3.3360947269900403	0.1674742789710398	
+3.3439999999999999	0.0504642972804711	9.8112674799972126	0.0244387789570361	0.0323495452138386	-3.0959410016251523	0.1504576486337995	
+3.3449999999999998	0.0444920454466932	9.8331812036283193	0.0187922059324153	0.0429346191337111	-3.1139354443379741	0.1630102630269592	
+3.3459999999999996	0.0518741120944797	9.8454489210947802	0.0254391374179968	0.0069163674086107	-3.3276815980891148	0.0410780799157474	
+3.3470000000000000	0.0248222415810598	9.8363192121911922	0.0194346794102543	0.1957068549540979	-3.2360253750842682	-0.0997052302787911	
+3.3479999999999999	0.0192847692783026	9.8287087636571453	-0.0032814990181063	0.0242898678783820	-2.9956575155226903	0.0344269080399440	
+3.3489999999999998	0.0374968755293277	9.7952641969645899	0.0178525373748378	-0.0039587727977047	-3.1046329834005975	0.0473789614427444	
+3.3499999999999996	0.0228488405136451	9.8131156605176617	0.0240491249377275	0.2677548438090150	-3.1386728140979852	0.1414492600520817	
+3.3510000000000000	0.0351182990454889	9.8253208601711144	0.0035495685383420	-0.2045574966874323	-3.3092087200682982	0.1545295063180297	
+3.3519999999999999	0.0484566208376539	9.8170752152727587	0.0313776235168871	0.0769994644811045	-3.2299350624835692	-0.1080336440576013	
+3.3529999999999998	0.0426112803113226	9.8339294045929115	-0.0037400669914485	0.1140830982850188	-3.0501457478348897	-0.1077103327915580	
+3.3539999999999996	0.0430634723563435	9.8138933957103589	-0.0004548123720330	0.0301551503666011	-3.1035818080669291	0.2064410698983374	
+3.3550000000000000	0.0517326219302621	9.8081242001970121	0.0229166473431511	0.3523939374343373	-3.4282110981757028	0.1193721915394429	
+3.3559999999999999	0.0263993276518493	9.8156505277690034	0.0155442110925522	-0.0871476622422826	-3.1989783827001661	0.3602389590239004	
+3.3569999999999998	0.0367636945859582	9.8400578170110844	0.0227248805305353	0.0888902751966608	-3.1576920934761086	0.1525395370102405	
+3.3579999999999997	0.0503706563886271	9.8139982151316243	0.0088000864545004	-0.0427563909601768	-3.3943762195610301	0.1395052372325380	
+3.3590000000000000	0.0337751969292824	9.8194446883776703	-0.0092765378199127	0.0126780031774969	-3.3674367694905540	0.0868687335092191	
+3.3599999999999999	0.0200716555030513	9.8331707074922416	0.0205145049727069	0.0779609425144883	-3.0444741729807756	0.1590388885747669	
+3.3609999999999998	0.0445908168494832	9.8119774167169940	0.0159475839661475	0.1183435689327541	-3.3775053089121014	-0.0051797691644925	
+3.3619999999999997	0.0508034280279904	9.8185907620192090	0.0142237661943252	0.2790566993195091	-3.1115077753226617	0.0003539147590993	
+3.3630000000000000	0.0631813074125609	9.8140817633241468	0.0259163137644771	-0.3093721081977695	-3.1561060733720199	-0.0660057784169350	
+3.3639999999999999	0.0317253489521634	9.8142684058648886	-0.0124379901806309	-0.0977021147684607	-3.1835119372046612	-0.0402376589529585	
+3.3649999999999998	0.0502823734828457	9.8261238810943343	0.0082260091787025	-0.0562726163857525	-3.2783459492234797	-0.1883801837070420	
+3.3659999999999997	0.0250872477745169	9.8287816282738039	0.0269673161769537	0.3265377987723387	-3.2201553475535869	0.1953845883258596	
+3.3670000000000000	0.0496067239227071	9.8495416162931146	0.0337742757834464	0.2059280501860931	-3.4282228465944709	0.1257973980040216	
+3.3679999999999999	0.0536446170567372	9.8519944573576428	0.0281960145173858	0.2702474026384627	-2.9996223084216402	0.1400694932852517	
+3.3689999999999998	0.0478266674253568	9.8212730601040192	0.0248780159133555	-0.1256316131844148	-3.3993455693968668	0.0373036992793309	
+3.3699999999999997	0.0323078070052492	9.8157447257542376	0.0352472331321393	-0.0642847254679478	-3.2336844834933158	0.3856304746060740	
+3.3710000000000000	0.0359070872358500	9.8252095676153495	0.0115954110664327	-0.0067632479554693	-3.0191296582433074	-0.2487935520975984	
+3.3719999999999999	0.0301931414869112	9.8089283918045673	0.0046366629606510	-0.0904864899296646	-3.1940030028351227	-0.2888400142682058	
+3.3729999999999998	0.0470586937813090	9.8165844285765136	0.0119122623793982	-0.0488587073114413	-3.2099575289049986	0.2803477125276915	
+3.3739999999999997	0.0700064877671698	9.8167322909250672	0.0224093507601431	0.0097654331892752	-3.0887143305336831	0.1091805866340738	
+3.3750000000000000	0.0389273094407574	9.8197132192784693	-0.0040237130649087	0.0582311581887829	-3.1498052741088021	0.4002166333496580	
+3.3759999999999999	0.0309913550936548	9.8006011692530137	0.0228729474550657	-0.0158124542194811	-3.1706390329521401	0.1520877018016492	
+3.3769999999999998	0.0477185607198960	9.8305905136082732	0.0092114411188923	-0.0070126067846014	-3.1346424961678414	0.0573705158589834	
+3.3779999999999997	0.0432616874876066	9.8427887047772611	0.0176239247446580	-0.2668782384625384	-3.1029914019685814	-0.0430248796926081	
+3.3790000000000000	0.0478626156657510	9.8339362153006906	0.0139158250372681	0.0952009402923869	-3.1840574062394644	-0.0340185562771156	
+3.3799999999999999	0.0514784544590321	9.8275628864159277	0.0320423996141585	0.2798907938819626	-2.8012024371733277	-0.1508571035017912	
+3.3809999999999998	0.0309712652586987	9.8144094500914836	0.0091667823846249	0.3495809163207813	-2.9653407827237612	0.1752234284086174	
+3.3819999999999997	0.0327526352803114	9.8269793415140203	-0.0128845553097096	0.0878290438796963	-2.9112506157554350	-0.1647522266334419	
+3.3830000000000000	0.0377718786246358	9.8136605497607423	0.0190625560964653	-0.1204728062642120	-3.4163399141326987	0.2231033945289166	
+3.3839999999999999	0.0306220899075667	9.8349043581845432	0.0260555048886184	-0.0080040315081159	-3.1261206531853594	0.1395433851863749	
+3.3849999999999998	0.0428903161192414	9.8325978843045210	0.0026172082962213	0.4534975825199599	-3.1082003520565284	-0.1317758150065904	
+3.3859999999999997	0.0310931875219639	9.8326240477667817	0.0267732885831864	0.1623278400580478	-3.0496618212596496	0.1261402423766576	
+3.3870000000000000	0.0404505340440786	9.8274621446471073	0.0242821784101614	-0.0990562277968005	-3.0416860959252014	0.0427052940559592	
+3.3879999999999999	0.0548073397413878	9.8305106574610299	0.0447795383876873	-0.1050507792865341	-3.1333312762219645	0.1460300211809039	
+3.3889999999999998	0.0524808171153467	9.8216890170766575	0.0084766700256914	0.2125395422850074	-3.1224055326523121	0.0176105324219188	
+3.3899999999999997	0.0535994994598254	9.8145123227342115	0.0123335135513550	0.1099030579991923	-3.1270794087867149	-0.1457954626428424	
+3.3910000000000000	0.0418533403526123	9.8278759784632594	0.0076151521731381	0.1319520372911984	-3.1273587493701758	-0.0774968773827994	
+3.3919999999999999	0.0576836267568611	9.8377343240039430	0.0235133214248321	0.0121690352232087	-3.2225256912925242	0.2331842278799246	
+3.3929999999999998	0.0260896522314135	9.8269874293711084	-0.0049025371355096	0.0539096519433169	-2.8527895315176224	-0.2580726090713804	
+3.3939999999999997	0.0459495652078476	9.8002050845282973	0.0066184353358990	0.1084189194597684	-3.4307164690694769	0.2324720610082622	
+3.3950000000000000	0.0323011612023972	9.8151618124881743	-0.0015430563165938	0.1189017993482132	-3.0531606510331493	0.3628070324845698	
+3.3959999999999999	0.0555019442003195	9.8124089821683160	0.0280218245329273	0.0931231113000944	-3.3954303131626786	0.0143753079618719	
+3.3969999999999998	0.0369480690519133	9.8235503056450248	0.0340096924578692	0.1668135993222644	-3.2651057378193800	0.1367933379716346	
+3.3979999999999997	0.0472557342598964	9.8308761000490215	0.0236071591863988	-0.1254110443683426	-3.3705939250263519	-0.1167971382320669	
+3.3990000000000000	0.0556556902202672	9.8228519717530549	0.0203499512595179	0.0684956929929849	-3.0345218638542755	-0.0029333068424235	
+3.3999999999999999	0.0652937767557478	9.8238925770266725	0.0348611955176027	-0.0123538329621985	-3.2201484903450566	0.3405761652814172	
+3.4009999999999998	0.0538381542161322	9.8318948536050463	0.0147228037216914	-0.0657697913823307	-3.1062384664898710	0.1276865455670451	
+3.4019999999999997	0.0372166278761859	9.8048509085648803	0.0141794174141633	-0.0625790415424284	-3.0292773564132309	0.0370978699674461	
+3.4030000000000000	0.0367338054335909	9.8157565540170815	-0.0104046483291837	0.0678989258675053	-3.0931041334710283	-0.2271069815322672	
+3.4039999999999999	0.0085376042562617	9.8269312112430516	-0.0037372129540925	0.0170039059302665	-3.1317297005470506	0.1346242665895413	
+3.4049999999999998	0.0434700496662696	9.8500265398424904	0.0264932418019422	-0.0947530969882487	-3.2786291156726812	0.1440736237168662	
+3.4059999999999997	0.0330172348731745	9.8149567231218953	0.0081248469350277	-0.0527924838305084	-3.3378582321767833	0.4334622263672445	
+3.4070000000000000	0.0408422249483071	9.8101198397273155	0.0256585588072761	0.2494517509519401	-3.0723017276852667	0.3475872356192847	
+3.4079999999999999	0.0414097845503864	9.8371833812362670	0.0094358603617807	0.2379407978729236	-3.1612008841922590	0.1604345568867482	
+3.4089999999999998	0.0589591365868149	9.8143656854165027	0.0024496795254735	-0.0530316155883237	-3.1694979926716380	0.1375130754222997	
+3.4099999999999997	0.0375388704942162	9.8144193840167873	0.0033634306178978	0.0468281568591619	-3.3317481248366105	0.0653142856170370	
+3.4110000000000000	0.0359249087372466	9.8428017616241910	0.0283772530060833	-0.0367637415911724	-3.1601520951779651	-0.1747275917092410	
+3.4119999999999999	0.0236655137310505	9.8183916289754176	0.0025524980016002	0.0085240779022563	-3.1836121535693946	-0.2711089663268333	
+3.4129999999999998	0.0504464457268534	9.8039483927093780	0.0262607458011877	0.0923861122331708	-3.2283386041641489	0.1358041518620777	
+3.4139999999999997	0.0458595924633153	9.8019807855360561	0.0310367002133908	-0.0959100126216086	-3.1736671347158514	-0.0820653821915212	
+3.4150000000000000	0.0494161238503844	9.8243608515710239	0.0077742535690365	0.1124935569774344	-3.0718668862259211	-0.0767503480040911	
+3.4159999999999999	0.0471444593122522	9.8240590879290490	0.0342710506999866	0.1331618603708040	-2.9567145317627332	0.1490577738095014	
+3.4169999999999998	0.0496032754783563	9.8292154074759495	0.0294814519481875	-0.1953041681797075	-3.3396066912499589	0.2964864491682112	
+3.4179999999999997	0.0413241033133951	9.8133952467389811	0.0313505364263420	-0.1344120886499800	-3.0113514543971736	-0.0954643982036178	
+3.4190000000000000	0.0315665956330951	9.8201108533033707	0.0330178521652686	0.2537147384823883	-3.2072462318305215	-0.0786205622242511	
+3.4199999999999999	0.0286217097587871	9.7964436004290754	0.0248024160206684	-0.2094995818964875	-3.0164575219396870	0.0720341004533173	
+3.4209999999999998	0.0546976204644920	9.8355556197541407	0.0206399181856929	0.1316520378077213	-3.2594950641318472	0.2321821585735633	
+3.4219999999999997	0.0334608014248529	9.8010322565151462	0.0141242035111017	0.1118372148793767	-3.1824911896234194	-0.0441327476816240	
+3.4230000000000000	0.0675432523028342	9.8196678846884868	0.0435874353382742	0.2407796502701168	-3.2286185171464385	0.2425155732990428	
+3.4239999999999999	0.0309047269661927	9.8159197949149366	0.0274597505117773	0.0131285782144986	-3.2365058201482357	-0.2763741780672804	
+3.4249999999999998	0.0447607705294784	9.8173350657024177	0.0401236768664802	0.1343731902298982	-3.1066889126138819	-0.1183294705140724	
+3.4259999999999997	0.0587759327848539	9.8402521918777488	0.0180303490079144	0.0700650775966177	-3.1773349729252875	-0.2874031321614089	
+3.4270000000000000	0.0454495817848392	9.8284090440822141	0.0299955808594840	0.0363552232454415	-3.0634021793019426	-0.0369010767804766	
+3.4279999999999999	0.0514243679971741	9.8149197281624776	0.0100795563365303	0.0122356040413762	-3.2833356776425129	-0.0352069014119956	
+3.4289999999999998	0.0252243871947905	9.8013306662700383	0.0260647718923710	0.0997108838551999	-3.2020753115767673	0.0960484461832052	
+3.4299999999999997	0.0488544935084805	9.8183313890151602	0.0131959400177200	-0.3328821954521254	-3.1209992019215975	0.1091240545006116	
+3.4310000000000000	0.0602640592350501	9.8243936800230571	0.0232723643337916	0.0518857980111459	-2.9681385066413948	0.3368278927091144	
+3.4319999999999999	0.0514011869369075	9.8437942051905907	0.0109202570623755	0.2036864523564108	-3.3705258185292108	0.0611805117032361	
+3.4329999999999998	0.0233133136375808	9.8048648434213757	0.0256112050890528	0.2098454561438693	-2.9999514443407800	0.1514945424669288	
+3.4339999999999997	0.0290464348528618	9.8067517366059587	0.0352835899862737	0.1256095387194711	-3.4262376524451454	0.2578016081732992	
+3.4350000000000001	0.0605551902707532	9.8185974849500983	0.0181469257957218	0.3456664913713656	-3.2255777198991220	0.2166543138548574	
+3.4359999999999999	0.0477179278761755	9.8393516177023361	0.0121577205084305	0.0775162605574515	-3.1814457013451949	-0.0351747138453489	
+3.4369999999999998	0.0467302772232415	9.7859888484656210	-0.0050285704517692	0.1527385578355978	-3.0864195569151645	0.1372165199586895	
+3.4379999999999997	0.0391373444707863	9.8443625301150366	0.0041192153892864	0.1447222388638290	-3.2235222267645463	0.2772285676240561	
+3.4390000000000001	0.0479441297046700	9.8196431101878225	0.0073708063006307	0.0947618703370554	-3.3774350615825335	0.0335157832419274	
+3.4399999999999999	0.0492846392685660	9.8160631803154796	0.0224409645581160	-0.0670513344790669	-2.9199486299930375	0.0227880355860508	
+3.4409999999999998	0.0383384173156203	9.8295174880687881	0.0164215918649158	0.1363326822082902	-3.1985098316153384	-0.0520286659513746	
+3.4419999999999997	0.0535473384670576	9.8073392476503862	0.0344871598976473	0.0086137732709793	-3.2718019648993564	-0.0154669802663389	
+3.4430000000000001	0.0527538626714247	9.8137828399295994	0.0134219603885310	-0.0524689796013312	-3.1392884033404549	-0.0085180361892684	
+3.4440000000000000	0.0361624416972132	9.8370965254405522	0.0243743984505534	0.2102190213459131	-3.3554519646080787	0.2061249571763555	
+3.4449999999999998	0.0437945983451916	9.8197008103554104	0.0174396601764465	-0.1706824906956200	-2.8595010475092013	-0.0490449980464481	
+3.4459999999999997	0.0552858324155855	9.8174063631556336	0.0486527966598827	0.2571206665624182	-3.3636730271934074	0.0774122602116792	
+3.4469999999999996	0.0330885481682987	9.8285378847713023	0.0066198096654333	-0.2057266739169040	-3.3953473761441653	0.1797347816916199	
+3.4480000000000000	0.0336358280022549	9.7976306859519493	0.0094069526011240	0.1271085389133664	-3.2461531856013259	0.1177839883610082	
+3.4489999999999998	0.0423330249613038	9.8253712804295894	0.0168361954518698	0.1789859514210302	-3.0996009021008510	-0.0019003420317585	
+3.4499999999999997	0.0410296316981397	9.8187957174974070	0.0093037192773449	0.2910532426260642	-3.0528239564776514	0.1686839834715561	
+3.4509999999999996	0.0417325565115030	9.8220640046859504	0.0004483386227499	-0.1233602684093025	-3.2234195279200279	-0.0700563155289406	
+3.4520000000000000	0.0639238722916442	9.8000114023697780	0.0202672505175170	0.0196125175840882	-3.5101218244037558	-0.1210361082170644	
+3.4529999999999998	0.0563237064095031	9.8117133426057670	0.0110972008206814	0.2092685436948422	-3.1056635348113351	0.1389456165998246	
+3.4539999999999997	0.0696027241239799	9.8331046949078136	0.0209817527832707	0.1933174889869669	-3.0678252355295461	-0.0564458668548053	
+3.4549999999999996	0.0548781436656570	9.8218536851312237	0.0275963622826241	-0.0354386341545129	-2.9997816422743022	0.0927505826818420	
+3.4560000000000000	0.0354455351957527	9.8276493465420742	-0.0020202545634923	0.3457958596368901	-3.3575090709251540	0.1117744806068029	
+3.4569999999999999	0.0647432051862082	9.8294854014934874	0.0129203284224460	0.1716912675347299	-3.1692841865413151	-0.0012744402140958	
+3.4579999999999997	0.0468111864702515	9.8191395365626484	0.0057052108970961	0.0090102628478067	-2.9214672777485791	0.3154987933138298	
+3.4589999999999996	0.0575569937508824	9.8231727796177406	0.0089687810552754	0.0416175779758941	-3.1781166122116962	0.1835864904493815	
+3.4600000000000000	0.0454650654330662	9.8171530134706533	0.0132831851489442	-0.0895978366026439	-3.2553539993910712	0.1088649232044211	
+3.4609999999999999	0.0454333196716769	9.8343640923708584	0.0450838525141802	0.1455294048615589	-3.0739894545072737	0.0167605462617917	
+3.4619999999999997	0.0500691197923354	9.8207472245071443	-0.0064091673308376	-0.0215873679241774	-3.3455420773821545	0.1589358979424897	
+3.4629999999999996	0.0553749782085952	9.8175554757918277	0.0291427475928216	0.2810520387739727	-3.2780518501974085	0.3100319672244530	
+3.4640000000000000	0.0635006496338339	9.8273891826434383	0.0153202540036936	0.0704718724337722	-3.2707966195448841	0.1007417732902114	
+3.4649999999999999	0.0422575570964652	9.8201545445957112	-0.0098760823630575	0.3250277168795936	-3.1789475406639229	0.0732990616617331	
+3.4659999999999997	0.0613025086659955	9.8255221374535822	0.0059010698856798	0.0273573056284566	-3.1539552079614057	-0.1163142847806182	
+3.4669999999999996	0.0446370221784711	9.8170411571495197	0.0233650354600005	-0.0556026978754288	-2.9850517520578159	0.0835148782748513	
+3.4680000000000000	0.0322611085122157	9.8342468634530711	0.0366673883086801	0.1815916225601761	-2.9562683026747312	-0.0882479807874597	
+3.4689999999999999	0.0493030092386966	9.8410239796828538	0.0027844332128848	0.3636607804407317	-3.1622629376692521	-0.0105049155822474	
+3.4699999999999998	0.0739131948273014	9.8232377868356711	0.0348339909942360	-0.2018376346681259	-3.3662081761490348	0.0087804460797242	
+3.4709999999999996	0.0540312470087864	9.8545444713434183	0.0208417881851338	0.0319126674377678	-3.1485431403480515	0.1925507180898298	
+3.4720000000000000	0.0500131969022648	9.8233482064695252	0.0149731995832048	0.1357898858872539	-3.0231788070950962	0.2441421616472287	
+3.4729999999999999	0.0509118318364049	9.8228954578655916	0.0130667440352068	0.0998187445247424	-3.1933865919105924	0.2293065931802949	
+3.4739999999999998	0.0376487567435227	9.8299362448403915	0.0142740556239178	-0.1304202924299852	-3.0390852411936264	0.1921774045858589	
+3.4749999999999996	0.0709125930973105	9.8262259440960058	0.0169896294091083	0.1283164109806291	-3.3059984069106130	0.4121231309585847	
+3.4760000000000000	0.0470061076467595	9.8158658508347454	0.0301415002860374	0.0428968445916180	-2.9909238230259070	0.1583988392232833	
+3.4769999999999999	0.0402246369269427	9.8219249600475091	0.0155752531979704	0.0372403184620028	-3.3256053617925514	-0.0815043793687963	
+3.4779999999999998	0.0677325524192215	9.8211273081760417	0.0494628099600417	0.0962958405358392	-3.2164401669771001	0.3701909412668581	
+3.4789999999999996	0.0367677378538591	9.8069417274512922	0.0350763261212520	-0.1819081319879746	-3.1835102591248745	0.0830485320193729	
+3.4800000000000000	0.0757086106313291	9.8118608604119082	0.0144301580197885	0.0677866481579467	-3.2640214957528273	0.1144693292325843	
+3.4809999999999999	0.0395608352680474	9.8193288223116557	0.0218764756272436	0.0017512187073591	-3.3266525856900993	0.2004787761126985	
+3.4819999999999998	0.0536215092872045	9.8223884315340673	-0.0084929608877919	0.1338335434818548	-3.1830240458430894	0.2228995816200409	
+3.4829999999999997	0.0580198543184613	9.8172015258099279	0.0164381534398612	0.1625194764253414	-3.3693756897695506	-0.0601624669400163	
+3.4840000000000000	0.0315491790028303	9.8128720664930036	0.0296882521575426	-0.2320013315745532	-3.2975609862355069	0.1224531890530807	
+3.4849999999999999	0.0765148922001993	9.8275374258923964	0.0208768545739816	0.1189349001231033	-3.0198765642770851	-0.1536184291662275	
+3.4859999999999998	0.0490492657889365	9.8179515193605642	0.0089623639109322	0.1530401994661756	-3.1335622121414271	0.2382044262812393	
+3.4869999999999997	0.0385756239632161	9.8081279768887182	0.0205087759716186	0.1353553658102136	-2.9913637219257545	0.2195278146842073	
+3.4880000000000000	0.0303551280484082	9.8288959850512594	0.0025760916897066	0.0382235717953492	-3.0036318995612823	0.1408360359308219	
+3.4889999999999999	0.0446703259823026	9.8133486833009975	0.0184305891373594	0.0541634514919101	-3.1209521008466838	-0.0821766766481034	
+3.4899999999999998	0.0568819011592027	9.8338381339072818	0.0135845870642325	0.0403865214915752	-3.4164105306224108	0.1576715083932775	
+3.4909999999999997	0.0892259450975340	9.8203113591470821	0.0109277398083733	0.0409435073163430	-3.3280205120201556	0.1687082322569228	
+3.4920000000000000	0.0445845883687812	9.8041837912775058	0.0277631961812300	0.1592198566931319	-3.0998390505590168	0.1751829624832662	
+3.4929999999999999	0.0343919179905040	9.8153414764881699	0.0125265593989705	0.2145575948755854	-3.4381741932450485	0.1097240530981585	
+3.4939999999999998	0.0554878194568237	9.8142308641777269	0.0184345674658335	0.1143421247555157	-3.1160686958856130	0.1628006463992069	
+3.4949999999999997	0.0527015388200711	9.8446789710598068	0.0088848878641045	-0.0761426932528568	-3.2521201422023180	0.2168615280841295	
+3.4960000000000000	0.0405602073072727	9.8194565005417083	0.0040203178403502	0.2600906808660055	-3.0503603369964267	0.0210904711400512	
+3.4969999999999999	0.0598484802975276	9.7935324199432880	0.0193954649261614	0.0659579443287820	-3.2525091711069334	0.0787751357775632	
+3.4979999999999998	0.0698889502515898	9.8042471296690987	0.0345314389009934	0.0346626777746171	-3.0540468645487913	0.2833071336056017	
+3.4989999999999997	0.0610560912097569	9.8362209947166619	0.0282718183015828	0.0796554311067681	-3.2705010212932897	-0.0444598696228943	
+3.5000000000000000	0.0277060521237697	9.8437974929771581	0.0239760479309417	0.0190014143709392	-3.3141734210540879	-0.1166238853762469	
+3.5009999999999999	0.0420603631123827	9.8502028179901409	0.0308279190458297	-0.1021180254593795	-2.9234132361810370	-0.0499200178025477	
+3.5019999999999998	0.0775831456209835	9.8132216417013201	0.0315989178265247	-0.0793861404209041	-0.1442025826151917	0.1993584268095646	
+3.5029999999999997	0.0693649710572296	9.8160211234667951	0.0066440800201831	0.0239011422226644	0.0957329605386277	0.2182817983759954	
+3.5040000000000000	0.0399994071103705	9.8376037163106620	0.0189278720063706	0.1795186707935779	0.0060966424998499	0.0204667476140549	
+3.5049999999999999	0.0678123570081909	9.8367402987724031	0.0079969456005075	-0.0590840824297523	-0.0985667784255320	-0.0217798584723666	
+3.5059999999999998	0.0399136122799506	9.8181630024218691	0.0402706737894624	0.0721473762489032	0.0178347915402465	-0.0734659131547408	
+3.5069999999999997	0.0308257959133895	9.8211413298514554	0.0221098955893642	0.3985710708607039	0.1769696706512028	0.0676178411177943	
+3.5080000000000000	0.0411821025145922	9.8312164001726448	0.0243104120399700	0.2297432827721305	0.1448120814677993	-0.0281482864113177	
+3.5089999999999999	0.0593797689681078	9.8273233708187515	0.0362972099341610	-0.0765519409028497	0.0738167419115129	0.2719793798101907	
+3.5099999999999998	0.0444478100580524	9.8299394407523888	0.0169333793925915	0.0303651630311707	0.0666955456631875	0.1658904561365706	
+3.5109999999999997	0.0442216526520831	9.8316775234248013	0.0139467588841651	-0.0804821854783987	-0.0301664595447912	-0.1039398886534531	
+3.5120000000000000	0.0512561841793910	9.8285712733040871	0.0251568104959511	-0.1041758605660408	-0.0891138169801144	-0.0710986716665535	
+3.5129999999999999	0.0479100717595461	9.8030727317779540	0.0087933084279275	0.0816978901054866	-0.1061826872667348	0.2411423439148636	
+3.5139999999999998	0.0377046174742140	9.8048650894833322	0.0125276255165594	0.0433514220378788	0.0387968249948849	-0.0661554343331666	
+3.5149999999999997	0.0616822259723764	9.8090528259613574	0.0239565658778591	-0.0158011354486439	-0.1857644455092871	0.0914392011726112	
+3.5160000000000000	0.0566302031665221	9.8198770404462863	0.0160437039276765	0.0902098470815276	-0.2458179325452838	-0.0726842500260803	
+3.5169999999999999	0.0562418892199615	9.8170534877595461	0.0197008434566200	0.0427309209829315	0.1562614130061071	0.1715035197440302	
+3.5179999999999998	0.0628683202866047	9.8360144584504745	0.0042839039730996	-0.0263110969817290	-0.0883568772312125	0.1913177088559482	
+3.5189999999999997	0.0657851406283228	9.8189097072795182	0.0154301645804003	0.1218022018838984	-0.0501539110937626	0.3593603076370180	
+3.5200000000000000	0.0671371140889861	9.8099329833046678	0.0161883350711761	0.0393536697719227	-0.0969014397440372	0.0114355210442651	
+3.5209999999999999	0.0647716249594078	9.8426919322669466	0.0266389007748696	0.0265979338602048	0.0731199349304709	0.1502348277254588	
+3.5219999999999998	0.0521229390270283	9.8250350801403350	0.0269026134642201	-0.1997315405713191	0.1465257496634862	0.0647453819108280	
+3.5229999999999997	0.0711152083129715	9.8234678723795259	0.0123314981073756	0.3513372992010744	0.1167806380675333	0.2417013926554713	
+3.5240000000000000	0.0808833889771116	9.8117307603902368	0.0264075605014864	0.1484980398496299	0.1724687613252880	0.1486846038485183	
+3.5249999999999999	0.0580086783963655	9.8145548241479101	0.0151259277961537	0.2024312227609111	-0.0740985635160645	0.1316638528052940	
+3.5259999999999998	0.0564415715589011	9.8305665662573283	0.0319477267072490	-0.0847747666592466	0.0233402074577809	0.1264516397004462	
+3.5269999999999997	0.0444437900961521	9.8140271490759403	-0.0084252495060790	0.1364294711240455	0.0301625499925990	0.0264196194669731	
+3.5280000000000000	0.0558914944554965	9.8324852310986284	0.0396893305466517	-0.1233157499403204	-0.3667181136982210	-0.0337374925222173	
+3.5289999999999999	0.0383602600889588	9.8084307484640938	0.0029172315496480	0.0979253421787819	-0.1117055229277210	0.0204785250173945	
+3.5299999999999998	0.0659563525097281	9.8189621303821379	0.0002655184752981	0.0866547125302748	0.1328962586997905	0.1627343668211357	
+3.5309999999999997	0.0265912500721100	9.8332550716176357	0.0118584508645966	0.0152821867709921	0.0789261532676843	0.1723052243920107	
+3.5320000000000000	0.0726549102489677	9.8110939171099485	0.0135381581793655	-0.0600034861323914	-0.2040878988977567	0.1432493373367411	
+3.5329999999999999	0.0333651804927837	9.8287941316613043	0.0358360061657424	0.1283384699086789	0.0762380256253258	-0.0994386933929574	
+3.5339999999999998	0.0481609601459255	9.8239114668501557	0.0281370069511049	0.1133266134189195	0.3742143542370042	0.3390095654124428	
+3.5349999999999997	0.0715357190351786	9.8235420179164237	0.0236110106572525	-0.0448828185142873	0.0379343342937083	0.1864426111499729	
+3.5360000000000000	0.0308896410726256	9.8473949732590427	-0.0045849227332360	0.0649990242043521	0.2203858706294538	0.3494761520398738	
+3.5369999999999999	0.0559003537827469	9.8161775112099470	0.0257329787992677	0.1133792079426472	-0.0336523360904449	0.0031620754878686	
+3.5379999999999998	0.0565542970704129	9.8439137128479572	0.0164463430962159	0.1277119420946951	-0.0788514905705716	0.1326677556050565	
+3.5389999999999997	0.0417966607407918	9.8198671381379494	0.0135677992477356	-0.0922962586204446	-0.0935575454900427	0.2186329622903805	
+3.5400000000000000	0.0515798057259954	9.8093582713126501	0.0073909598669295	0.0457052066520999	-0.2381125541345012	0.0015987512475678	
+3.5409999999999999	0.0592551469634926	9.8189236549771657	-0.0054841655213231	0.0882910118482217	-0.1129830895593453	0.0733124472082638	
+3.5419999999999998	0.0692553491033716	9.8302508473943000	0.0105292921645736	0.2791947839493447	-0.2685792087455371	0.1109791463166764	
+3.5429999999999997	0.0341463838682201	9.8073910074801613	0.0442735393440888	0.1608174066932680	-0.0707025661623669	-0.0014166581375720	
+3.5440000000000000	0.0677281074562360	9.8196145853108234	0.0183577022292780	0.0341227368283582	0.0257967941614953	0.1892920628397019	
+3.5449999999999999	0.0540323627326662	9.8184379108293971	0.0176276009200973	0.3229998362208549	-0.0069457239710438	0.0693594849226568	
+3.5459999999999998	0.0495687406691593	9.8169391955964791	-0.0026808919056084	0.0518873499821465	0.1770225722408595	0.1038817244988020	
+3.5469999999999997	0.0418913940363301	9.8410243523146743	0.0337872531006009	0.2370022793628329	0.0044609277205503	0.2148294365269292	
+3.5480000000000000	0.0576616814043329	9.8370411127049664	0.0166871963863681	-0.0418888324693393	-0.2911049510400424	0.3559978571502571	
+3.5489999999999999	0.0457470967434961	9.8314393579352064	0.0181940523229602	-0.3287409398151870	-0.1221837313149536	0.0452753910205032	
+3.5499999999999998	0.0354768079923772	9.8035504778026628	0.0013487947875112	0.0105445907311916	0.1259085004318576	0.0604559388529631	
+3.5509999999999997	0.0651053858190820	9.8351815297047747	0.0133553354891451	-0.1233542905821769	-0.1585190311233631	-0.0572667191296527	
+3.5520000000000000	0.0510946624983584	9.8339900628306189	0.0194380944763906	0.1543281670468681	-0.1991353837390217	-0.0754814685263791	
+3.5529999999999999	0.0623219588727771	9.8170692894040297	0.0093316910709827	0.1721805909615279	0.1222944392406295	0.3029692403758054	
+3.5539999999999998	0.0499076322916107	9.8227206644436933	0.0133597822384523	-0.0299651449277805	-0.1270020657072747	0.0772938514700324	
+3.5549999999999997	0.0558528856500124	9.7939224746866316	0.0287512933516220	0.2646197767728692	0.2335680538026809	-0.0055999843070456	
+3.5560000000000000	0.0441024100724194	9.8328757844206436	0.0067707461722620	0.1136624648695228	-0.0977630697447997	0.1522269447226887	
+3.5569999999999999	0.0549295961348217	9.8297585906096678	0.0208735291172577	0.1855833712476305	0.0268861996151606	0.0674085416305035	
+3.5579999999999998	0.0500516816600108	9.8390641831072809	0.0149085509593273	0.3735962353549079	0.0520636858407073	0.0324669189140738	
+3.5589999999999997	0.0530072244130352	9.8263674875288434	0.0323051107005540	0.3043615438513964	-0.1284093784193938	0.0667961822379636	
+3.5600000000000001	0.0372512771229510	9.8203420883793608	0.0059799784688858	-0.0689646716077124	-0.1291323377840426	0.0972849761483842	
+3.5609999999999999	0.0529416345360404	9.8325041223485510	0.0158291592203826	-0.0099605502302366	-0.0354156700266713	-0.0315739503431796	
+3.5619999999999998	0.0527705127026044	9.8348862934086725	0.0308754368794711	-0.0464024519570826	-0.1071390585521397	0.1291879697483979	
+3.5629999999999997	0.0548492093115487	9.8257214379827822	0.0247704094335643	0.1657780613494816	-0.0942495687520146	-0.0171301848196542	
+3.5640000000000001	0.0404157233818457	9.8343066670020924	0.0227612781595308	0.1279898223833975	0.0219854971387429	-0.0729240037823464	
+3.5649999999999999	0.0570579837766420	9.8549061084932550	0.0278315050563933	-0.2090804506008104	-0.1184006162151504	0.2109675796207952	
+3.5659999999999998	0.0570240393286782	9.8186850161161043	0.0160843771311634	0.0114830133121691	-0.1887784153411131	0.0243121927935607	
+3.5669999999999997	0.0422508870198095	9.8326050937122442	0.0242829448199261	0.0205029106361916	-0.1095905096831570	0.3213112946143520	
+3.5680000000000001	0.0673469805682158	9.8104605943384193	0.0153492346266253	-0.1636035048434948	-0.1497996224075234	-0.1276063971821729	
+3.5690000000000000	0.0607509247516600	9.8278151458176666	0.0136650115284198	0.2739839805842988	-0.2050219289372248	-0.1736999249918985	
+3.5699999999999998	0.0530931547550254	9.8112706217989683	0.0133649822961658	-0.0402730655836175	0.3017606271511946	0.1839966493840185	
+3.5709999999999997	0.0497763561363663	9.8110785949229715	0.0182454414513780	0.0478239245770824	0.1076688638406749	0.1720818518625818	
+3.5720000000000001	0.0752001018603300	9.8248064623268352	0.0296701629400768	-0.0812275375486351	0.1319275975968273	-0.2000860376374190	
+3.5730000000000000	0.0743842122481633	9.8225912024101731	0.0457153738668327	-0.0886579706430513	-0.0879232364697960	0.2663988437720709	
+3.5739999999999998	0.0521820532436152	9.8240348702039491	0.0093447470345218	0.2794126599321442	0.1046409097309492	0.1587225713739538	
+3.5749999999999997	0.0712722461453573	9.8336133249059934	0.0342121132859608	-0.0244918552860786	-0.0715437515297394	0.0592071588709404	
+3.5759999999999996	0.0543962972321092	9.8081675543687012	0.0117080328435750	0.0829585768066675	-0.0039994167133462	-0.0021482733746521	
+3.5770000000000000	0.0315004595779897	9.8384326196758902	0.0225002236217375	0.0745426318171799	-0.1905225060689164	-0.0423872149608442	
+3.5779999999999998	0.0637180006473725	9.8206388711047925	0.0173517750348501	-0.1240480269969936	-0.3084418051527535	0.1043167795589877	
+3.5789999999999997	0.0722993763511994	9.8157995776788738	0.0098346148700449	0.0839341925468124	0.0370898630009451	0.1550515230642902	
+3.5799999999999996	0.0462095551123215	9.8186334243604367	0.0252096209220746	0.0850759060903058	-0.0480043354925092	0.2605113396995609	
+3.5810000000000000	0.0608113036939950	9.8263602908985348	0.0100570546583986	-0.1161049240979970	0.0986549515012269	0.1024800371776498	
+3.5819999999999999	0.0429253069231545	9.8283732199683893	0.0380880357757615	0.1464918198215228	0.2628052616137173	-0.0220365725143180	
+3.5829999999999997	0.0471314836624924	9.8333665224112501	0.0092850237147726	0.0353076586876330	0.3163985098255909	0.1000400932210214	
+3.5839999999999996	0.0540250042298479	9.8150915447648224	0.0256143065784043	-0.1284337956544738	-0.2964513795371075	-0.0581508507989900	
+3.5850000000000000	0.0615483249398068	9.8012948812446670	0.0129291250613617	0.0934576314694449	0.0016980787355277	0.2266386783753455	
+3.5859999999999999	0.0716329694593961	9.8314317493156960	0.0261593584804932	-0.1314451897635261	-0.2198886182856193	-0.0813861518374317	
+3.5869999999999997	0.0626491898564931	9.8056259025507817	0.0156170420319453	-0.2134548064382604	-0.0836926928342377	0.0530434879118060	
+3.5879999999999996	0.0546305505899067	9.7966089208788905	0.0223357947721142	0.0002516243671859	-0.3053521113453853	0.1493610258844851	
+3.5890000000000000	0.0601034531893012	9.8428370552438036	0.0379926873269749	-0.0838299821776602	-0.0416825843406797	0.1204925853442399	
+3.5899999999999999	0.0594928453274097	9.8288822534710096	0.0102389936782984	-0.0216241962589845	-0.2408902061444683	0.1632397090118163	
+3.5909999999999997	0.0340396455417202	9.8255630723310450	0.0334491800843452	0.0001257834388828	0.1979993832183167	0.4518411881508242	
+3.5919999999999996	0.0537478535607967	9.8148559340524599	0.0162391773326332	0.2084255945302934	0.0529541577092959	0.1768299764994253	
+3.5930000000000000	0.0805480565592925	9.8238669442339432	0.0227870224140248	0.0935177113544215	0.2006454406289692	0.2985258541818977	
+3.5939999999999999	0.0526746555064047	9.8212713277514609	0.0114469631160764	-0.1896162474456667	-0.1346790549353700	0.2685286600916620	
+3.5949999999999998	0.0606433375755975	9.8185110160275535	0.0112042696270500	0.0946681059635701	-0.1193659889987813	0.0474022092363390	
+3.5959999999999996	0.0731251895129910	9.8118990200885960	0.0276849347903896	0.0067485590231503	0.1168758725459868	-0.0618477450578123	
+3.5970000000000000	0.0766602753388655	9.8190076281281247	0.0316754066298929	0.0905101027264352	-0.0104327146665933	-0.0835126229310636	
+3.5979999999999999	0.0365337724456172	9.8052290208746804	-0.0041507094151603	-0.0424614842404308	-0.2876704822448335	0.0576037279510089	
+3.5989999999999998	0.0604911283677864	9.8132288847222497	0.0083217376245810	0.2137057661899156	0.0747502101636209	0.1720880217462965	
+3.5999999999999996	0.0413894546546590	9.8245337676638638	0.0291602203185363	-0.1307518140962192	0.1463280958382242	0.0527037716245885	
+3.6010000000000000	0.0482995500879784	9.8309332928274920	0.0097249528394228	0.1875769383388316	0.1266647464941715	0.0222157701530511	
+3.6019999999999999	0.0673309409934455	9.7990191108563334	0.0268530896622632	0.0714900131060452	-0.1173596825839424	0.1953163290166211	
+3.6029999999999998	0.0589089341729383	9.8010674217896785	0.0093526283515420	-0.1278789195593566	-0.0056123260838039	0.0961614032963119	
+3.6039999999999996	0.0723027710794265	9.8292162347031677	0.0210538272749075	0.1170619828251057	-0.0703203372937858	0.1314377711221945	
+3.6050000000000000	0.0629041942996448	9.8196405981311390	0.0353332717582634	0.1770793310482002	0.0619093722673071	-0.0038139470167362	
+3.6059999999999999	0.0794731453539539	9.8301379998297236	0.0136413755905451	0.0701138906739392	0.0711957200091523	0.1354704358828268	
+3.6069999999999998	0.0669836394718126	9.8262892067020253	0.0078831126975985	0.1878624504022514	-0.0236977983000538	0.2339453228120387	
+3.6079999999999997	0.0698968098237701	9.8217746222104445	0.0275714381384790	-0.0442632905712337	-0.0213852385774953	-0.0822045433875610	
+3.6090000000000000	0.0533592862213370	9.8347986192487920	0.0421464717439569	0.1881222487161683	0.0869091656715298	0.0181829349430886	
+3.6099999999999999	0.0619154234217670	9.8034071450343117	0.0269254263588118	0.0035546658405100	-0.2213845719789286	0.0860412058669564	
+3.6109999999999998	0.0445030960698392	9.8211458134549279	0.0244235218668070	0.0088599957012542	-0.0552448985453523	0.0257844309936829	
+3.6119999999999997	0.0412405305514889	9.8109954201360150	0.0210597812759510	0.2425501394056728	-0.1413671309426948	0.0115528987933975	
+3.6130000000000000	0.0566775315147449	9.8054450816401495	-0.0054162494661096	0.0960590692448619	-0.1098263491695649	-0.0483586680115469	
+3.6139999999999999	0.0411450362639465	9.8021731126690330	0.0107910120415858	0.2276621777428290	0.1188124690643653	0.0214956607453587	
+3.6149999999999998	0.0692349072766423	9.7993187853110655	0.0152747519137413	0.2147441012221006	0.0724803054457961	0.2305319709180293	
+3.6159999999999997	0.0443785395812741	9.8240954561923974	0.0123306497750752	-0.0757712113765723	-0.0866133730613376	-0.0257406536342289	
+3.6170000000000000	0.0592928425153809	9.8373464895474978	0.0189721347250505	0.1912767522955548	-0.1283112564487971	-0.0890354515387203	
+3.6179999999999999	0.0619894908169316	9.8278126482823733	0.0319343754488280	0.1685104829096100	0.0474596462397602	0.1933934754802638	
+3.6189999999999998	0.0385731446372794	9.8219452642487415	0.0347190905705404	0.1343661092813721	-0.1331470317011625	-0.2237229084345479	
+3.6199999999999997	0.0546548478133268	9.8224544242520491	0.0065811834968246	-0.1942590922024613	0.0202709183467978	0.0577493208142129	
+3.6210000000000000	0.0561202375319330	9.8337030446127667	0.0222578237259582	0.0255411399546323	-0.0120921859380860	0.2320389528872553	
+3.6219999999999999	0.0621156663596255	9.8324334688240977	0.0144737453110930	0.2291683358879690	-0.0184092896183390	0.1195089873619320	
+3.6229999999999998	0.0579061498163727	9.8145873341909553	0.0182404454564516	0.0696520136212873	-0.0327712272893866	0.1685957972629347	
+3.6239999999999997	0.0665206895377404	9.8006759620211525	0.0343202444620846	-0.1544909712661978	0.0997931296316057	0.0684213139292080	
+3.6250000000000000	0.0412347270509750	9.8123757901332862	0.0344583302781467	0.1397002007220485	-0.1225127468788090	0.1765225086597570	
+3.6259999999999999	0.0586904371526450	9.8271722917079760	0.0205548598821643	-0.0346504410822193	-0.0030689428725782	0.2168694622649814	
+3.6269999999999998	0.0577934189522245	9.8024423611686426	0.0024309026747085	0.0854309642798897	-0.2699420013553712	-0.1313086961982404	
+3.6279999999999997	0.0476810480543744	9.8195983950146015	0.0237701674546073	0.1719925415003378	0.2035060827467130	0.0308502663533637	
+3.6290000000000000	0.0573222807251759	9.8143306978296003	0.0034082224496357	0.0061447404907715	-0.1723430554425187	0.1065985534320896	
+3.6299999999999999	0.0669831476953647	9.8537521826078791	0.0386007964832776	0.1758216461980485	-0.0044047146498879	-0.1457018564581177	
+3.6309999999999998	0.0683823960092069	9.8363965934739532	0.0223264829689612	-0.0618017113996205	-0.1379032351551258	0.1542717136077348	
+3.6319999999999997	0.0411197369347295	9.8170063552841036	0.0061432331810200	0.2722193067262636	-0.0549190457173983	-0.0263336629731593	
+3.6330000000000000	0.0866356645991261	9.8248417904476835	0.0150197935839362	0.3127213880910101	-0.2471357169286899	0.1872928754688326	
+3.6339999999999999	0.0508310803712236	9.8347208512391511	0.0173169389806744	-0.0829794181223037	-0.2563716870887381	0.1320816272441913	
+3.6349999999999998	0.0589703640569601	9.8162967625081592	0.0225513987157127	-0.1675986088077361	-0.1548179588162195	-0.0957053728095952	
+3.6359999999999997	0.0520403013519733	9.8237847756763124	0.0257631098552219	0.1655650321733174	-0.0102910798762498	0.2569014265188456	
+3.6370000000000000	0.0639945161029341	9.8188009728898642	0.0185969804294300	0.1734773517765300	-0.3118760010067396	0.2334262352584368	
+3.6379999999999999	0.0803432014161008	9.8292953214756853	0.0056325310534840	-0.0278543430259197	0.1043613625488693	-0.0472412950377768	
+3.6389999999999998	0.0574487014083748	9.8351965715645324	-0.0038360814155837	-0.0096339755626931	0.0040280974530676	0.0875978996319649	
+3.6399999999999997	0.0500384244206574	9.8189870247699460	0.0235288651097896	0.1316429901521282	0.0997445347218870	0.1676038468470318	
+3.6410000000000000	0.0450711909413204	9.8140236839568029	0.0155093283325722	0.1378073874607358	0.1663638750171348	0.1978027154009435	
+3.6419999999999999	0.0530420891225328	9.8104612525212218	0.0221416554304278	-0.1354619290665176	0.1076749635432188	-0.1304825656419414	
+3.6429999999999998	0.0473988612091880	9.8206929028972105	-0.0013848995652018	0.2809785079640346	0.1223297288208013	0.0295085527275630	
+3.6439999999999997	0.0589020399005884	9.8312195490719230	0.0168328555428602	0.2085463977630126	-0.0296649826090968	0.1914945757614858	
+3.6450000000000000	0.0601740309253638	9.8239515100294241	0.0215933021137723	-0.0826260378940155	0.0057685516503693	-0.0431798824282909	
+3.6459999999999999	0.0435635361569451	9.8381662516812476	0.0347889951317866	-0.0110324870213590	0.1006810264801725	0.0816830606536102	
+3.6469999999999998	0.0523794449571439	9.8312027103866644	0.0287606807290954	0.1217456561716320	0.3220825581443659	-0.0537244725710921	
+3.6479999999999997	0.0336227072036169	9.8228022783933113	0.0058852301523986	0.0484676571697913	0.1354791510626751	0.0588941398767201	
+3.6490000000000000	0.0627877337084728	9.8224323960286259	0.0285684224136650	-0.1399676718468300	0.2339656558178159	0.3215488347358231	
+3.6499999999999999	0.0693847280879686	9.8266713745649401	0.0108308183890451	-0.0400435094593714	-0.0003783017472267	-0.0809562713424260	
+3.6509999999999998	0.0521353285465635	9.8295419821797250	0.0339414140783740	0.0030016497538621	0.0793159688780973	0.0437042582416436	
+3.6519999999999997	0.0481875459378829	9.8069877905939151	0.0452630563360855	-0.1424077805350800	0.1364526245217256	0.1995009314917736	
+3.6530000000000000	0.0528754798875075	9.8330415189992664	0.0261957054995150	0.0274043771767542	-0.3620492412555897	0.0391031284053317	
+3.6539999999999999	0.0743580676428076	9.8118711958572646	0.0528906801103152	0.1001847289043579	0.3308176338758528	0.2353260147406376	
+3.6549999999999998	0.0610677847392874	9.7982349828897384	0.0288599143851262	-0.0546012352756448	0.0794519553558556	-0.0287703765087175	
+3.6559999999999997	0.0511713476108252	9.8167071476657046	0.0077809859298641	0.2250511800838041	0.0661251557534212	0.1418828937937043	
+3.6570000000000000	0.0471888702278754	9.8056036978517138	0.0247406543399858	-0.0126932332704088	-0.0335934910461812	0.1586791632275383	
+3.6579999999999999	0.0820565154814038	9.8488743060499644	0.0164771858177818	-0.1407866171341261	0.3093062082648835	-0.0029574506248636	
+3.6589999999999998	0.0604217875193941	9.8079282486598878	0.0115754675450114	0.1189770105692478	-0.2526476468310446	0.3646996378936780	
+3.6599999999999997	0.0694072265371293	9.8072774746847902	0.0163233871757743	-0.0618036737639385	-0.0950807417573695	-0.0944079284843269	
+3.6610000000000000	0.0664473049043727	9.8185151964585895	0.0313219828835156	0.2491239711331139	0.1610395913478418	0.2837030567579427	
+3.6619999999999999	0.0492406469888871	9.8302802982537472	0.0082824520118465	0.0032408726424830	0.0642868626183925	-0.2636459008566603	
+3.6629999999999998	0.0410374710792693	9.8058403322888879	0.0194418280476265	0.1485792816505485	-0.0364151420101293	0.1308049365660368	
+3.6639999999999997	0.0612773712611554	9.8372707243676452	0.0044289591827385	0.3834315003836393	0.0777965859629505	-0.0006214815704001	
+3.6650000000000000	0.0675923536635258	9.8097511886493329	0.0124034007899021	0.1310187950836743	0.0180858075122244	0.2107912149742550	
+3.6659999999999999	0.0566627494446797	9.8174386876415749	0.0222905385252907	0.0481644916907212	-0.1559008712955692	-0.0157620742300280	
+3.6669999999999998	0.0470348442746828	9.8300130699774400	0.0046442148075125	-0.0974900512092794	0.0058557735211679	0.2503357218787945	
+3.6679999999999997	0.0630388728620865	9.8192133024473662	-0.0019986110505935	-0.0625768576153552	0.1561595791556630	0.1093429065861065	
+3.6690000000000000	0.0652687985855557	9.8362400474918132	0.0141914376819674	-0.0888352194369413	-0.0325680847376082	0.1474332150052096	
+3.6699999999999999	0.0453598900370522	9.8235239101010077	0.0263019238612035	0.0516356831122356	-0.0341836531287681	0.0583079643575423	
+3.6709999999999998	0.0484311064028332	9.8356538616000542	0.0202199034385488	0.1302400708217204	0.0220751729357681	0.2911729929722055	
+3.6719999999999997	0.0333288032900458	9.8267621746597040	0.0040319496433953	0.0909163162360851	0.0076588522198531	0.3414859490265942	
+3.6730000000000000	0.0370267046728251	9.8404583299191000	0.0138414728937997	0.0817506073343666	0.1317049196827289	0.0306764411855950	
+3.6739999999999999	0.0714419847522871	9.8511694178160152	-0.0019900163453755	-0.0687854215163001	0.1034695815584599	0.2367361665812963	
+3.6749999999999998	0.0329284288403688	9.8234740488143224	0.0132133189923274	-0.2236703369711969	-0.0202352405101348	0.0786888691062031	
+3.6759999999999997	0.0603042504221452	9.8249251570555600	0.0033012696204167	0.0981223930477248	-0.1677501381390638	-0.0528650597768355	
+3.6770000000000000	0.0624268633622593	9.8312732302912877	0.0097186639170548	0.1022774808637851	0.1813533800690089	-0.0156116953473074	
+3.6779999999999999	0.0594548147262490	9.8305132408200961	0.0030138500116448	0.0420923651964395	0.0115022176360467	-0.0477614919666602	
+3.6789999999999998	0.0628756877455751	9.8187214591557552	0.0367771845254644	0.3831026212856217	0.2149369752180649	-0.0543115140916089	
+3.6799999999999997	0.0522669954643883	9.8127210894699317	0.0052270359431548	0.0042335769484134	0.2924919875383739	-0.0936632148717311	
+3.6810000000000000	0.0263813410629722	9.8441835306180128	0.0047145930292350	-0.0478992386112347	-0.1070388732507775	0.1785000410195541	
+3.6819999999999999	0.0486212609601529	9.8382727560765311	0.0064573039408477	0.0927630168055387	0.1152683072336080	0.1197596535269590	
+3.6829999999999998	0.0581873396802207	9.8402332773626515	0.0175409516083541	0.1927841020733184	-0.0057259509031330	0.2471564510031993	
+3.6839999999999997	0.0533295300285947	9.8138299102430082	0.0473312311042125	0.0876316682160263	0.1990349867722991	0.2595279024382168	
+3.6850000000000001	0.0459138526049069	9.8461705852612251	0.0012592173207652	0.1464157101316595	-0.0587215509026760	0.1302705766092022	
+3.6859999999999999	0.0597967631422853	9.8175593556629206	0.0210653770958838	0.1869556301782554	0.1935732196667617	0.4016988767841620	
+3.6869999999999998	0.0482616287585416	9.8172798138832551	0.0369558043935883	0.3302926101778600	-0.0981166196998697	0.1934783091886048	
+3.6879999999999997	0.0529715329929474	9.8159910461993753	0.0166797170374111	0.1010205512321311	-0.2317856520154140	-0.1610602756218332	
+3.6890000000000001	0.0454039379464232	9.8228101428836485	0.0217953230579400	-0.0374207092485436	-0.1156138819192629	0.2634044501225991	
+3.6899999999999999	0.0400690203526022	9.8267509946688811	0.0097378575021502	0.0292839339198241	-0.0171164730442365	0.0539206250780969	
+3.6909999999999998	0.0587513401331691	9.8337679977877546	0.0410040299385017	-0.0871509009634184	-0.1570681707523241	0.0162904990132489	
+3.6919999999999997	0.0730262260308847	9.8166563765048345	0.0389008583566909	-0.2336486076483456	-0.1863495861093942	-0.2047401230706127	
+3.6930000000000001	0.0672748860906960	9.8108539942162043	-0.0005917800646252	0.0313837343357621	-0.1973351721531690	-0.0083452531749172	
+3.6940000000000000	0.0527549508213843	9.8378530951331555	0.0096867105150461	0.1713740835826953	0.0084537321999858	0.0188396593800812	
+3.6949999999999998	0.0521502729506036	9.8196920583430654	0.0206855287694186	-0.0579415789225370	-0.0015526838411962	-0.1125874916587031	
+3.6959999999999997	0.0659555999726322	9.8192489428168841	0.0025989539340334	0.1009928123813891	0.0221029119480149	0.1596015358893058	
+3.6970000000000001	0.0453917426606026	9.8035646477680665	0.0197925718061262	0.2444845377086231	-0.0129346440619118	-0.0505022958616634	
+3.6980000000000000	0.0377667380181481	9.8339510278199729	0.0140267159585745	0.0853934815140356	0.3870401504507670	-0.0868118585526768	
+3.6989999999999998	0.0665296437739322	9.8292655545637722	0.0343068523898921	0.0385860665158076	-0.2199973090483633	0.0446066146514906	
+3.6999999999999997	0.0549786310972343	9.8127892866216424	0.0212257047924864	0.0197521142167286	-0.2025769419633446	0.0933260636402014	
+3.7009999999999996	0.0598667769009747	9.8221169224035894	0.0377854350231700	0.0521080321729362	0.0293096947835685	-0.1767702363381081	
+3.7020000000000000	0.0594641528379877	9.8204959927282225	0.0401988252715263	0.0389698254186365	0.0614100084945111	0.0288070860471661	
+3.7029999999999998	0.0505655085682975	9.8441592006508092	0.0240697039432217	-0.1071907749241110	-0.2706523980327167	0.1012742725096557	
+3.7039999999999997	0.0355156733461094	9.7973445957138594	0.0089087370831299	0.0515012875342964	-0.0125869872874515	0.0942929944007829	
+3.7049999999999996	0.0479887643544401	9.8299993045067193	0.0312301100298696	0.0630913318933938	0.1909805773618472	0.1532934064761062	
+3.7060000000000000	0.0485057799198068	9.8171498479115691	0.0002803497681003	-0.1314737500615972	-0.2072428806011312	0.3148552853830949	
+3.7069999999999999	0.0530961759503601	9.7773874200988917	0.0200385647842889	0.1610543278776624	0.0401548551655411	0.2073046709069294	
+3.7079999999999997	0.0593444067839066	9.8282648567769968	0.0174033442739960	-0.0497544478867671	-0.2712310673194873	-0.2579211708786679	
+3.7089999999999996	0.0442413795718589	9.8181672452544184	0.0224812121944011	-0.0000009587943987	0.0222333285170214	-0.1659876667308101	
+3.7100000000000000	0.0724764414786642	9.8471158254061137	0.0091245451891333	0.0095602154433648	0.1420831532423082	0.1725013840436125	
+3.7109999999999999	0.0524295832930958	9.8296230786059180	0.0252053675262494	-0.2872666215651750	0.0115456866156901	0.3317001101401624	
+3.7119999999999997	0.0343963026404066	9.8182813853109909	0.0150057792537659	0.2064269190386787	-0.0567089080815835	-0.0193480025228486	
+3.7129999999999996	0.0490926963262179	9.8179287583125188	0.0243377346748478	-0.0831614055387810	-0.2141124168056133	0.0775373672256258	
+3.7140000000000000	0.0367507451745915	9.8007354941579994	0.0243776875987215	-0.0923052054146884	-0.2466094066543996	0.2886090735519793	
+3.7149999999999999	0.0657761869299559	9.8226240355659442	0.0171601883695545	-0.0146499562964646	0.0237375254971619	0.1096363052554394	
+3.7159999999999997	0.0631384002678433	9.8164331677476522	0.0057553269881568	0.2722657563955655	-0.0808496995758565	0.0239868653955193	
+3.7169999999999996	0.0640992866289098	9.8231182604704941	0.0263186854146383	0.3598188363624747	-0.3070875938465426	0.0888848830515598	
+3.7180000000000000	0.0549809339665823	9.8258426918024409	0.0218125820292974	0.2153948003276241	-0.0892221675406306	-0.2678628252747658	
+3.7189999999999999	0.0717005519426589	9.8086759543253805	0.0244560721214952	-0.0414138294185907	0.2454712206955531	0.1969957858542682	
+3.7199999999999998	0.0454055444461100	9.8317558381284638	0.0294244534692539	0.0859306884530391	-0.0040157023713121	-0.1352450244515937	
+3.7209999999999996	0.0445407768491785	9.8153024708028482	0.0147650342141904	0.1737248010275039	-0.1211023996957719	0.0944982462280884	
+3.7220000000000000	0.0448516360119190	9.8189969019623984	0.0342595403495877	-0.0892314212102915	0.1762849871731916	0.2779236281117666	
+3.7229999999999999	0.0513029435378574	9.8260217301936876	0.0025681887675568	-0.1223695060726019	-0.0135785961716236	0.3023510079183838	
+3.7239999999999998	0.0534987350872650	9.8172092794711308	0.0003236961845705	-0.0169886824100169	-0.2632234035328423	0.1453471389491863	
+3.7249999999999996	0.0596152339136055	9.7967433195237561	0.0136500369544192	0.2052283357670971	-0.2183492080442518	0.0259239350582808	
+3.7260000000000000	0.0390847010252301	9.8291497908612904	0.0260019360033956	0.1263290589179356	-0.1622909144309162	0.0487304462864195	
+3.7269999999999999	0.0607746924071374	9.8322302485611228	0.0126393941091997	-0.0146477884606172	0.0909297878769002	-0.0715043114526182	
+3.7279999999999998	0.0548896586145952	9.8196031688928169	0.0345899267060816	0.0909783850239661	-0.1332471676698136	0.0821477974084024	
+3.7289999999999996	0.0476912843787903	9.8213573734733046	0.0254065650948583	0.1831843316925533	-0.3445404295641252	-0.1460857958952906	
+3.7300000000000000	0.0605107770819174	9.8019671023086765	0.0041711740152697	-0.2774321196736794	0.0330875562144351	0.0191845747779763	
+3.7309999999999999	0.0340879009925010	9.8139285869801594	0.0411763838173102	-0.1937109450153005	0.0808822030416596	0.2276653232516186	
+3.7319999999999998	0.0608791656511373	9.8201949872344940	0.0227885995582548	0.1166977267806095	-0.1471506184949822	-0.1563593830935940	
+3.7329999999999997	0.0668131696286852	9.8458885760031052	0.0274109482060083	0.1159871659822304	0.0970254629348276	0.2216556183741659	
+3.7340000000000000	0.0666861485584270	9.8083621699375847	0.0236185375264219	0.0384586778518681	-0.0890265098847139	0.2325502010660357	
+3.7349999999999999	0.0594753209058188	9.8486976763982099	0.0144173938877291	-0.2480688565023445	-0.0928869307895187	0.1205285224068568	
+3.7359999999999998	0.0420003414431954	9.8487208929809693	-0.0057302040349206	0.0804647696206294	-0.0256747509977935	0.2010591684927687	
+3.7369999999999997	0.0606464547707622	9.8290569910703542	0.0206108912763457	0.1383946317627948	-0.0265543521173360	0.1790866611941560	
+3.7380000000000000	0.0619212923119319	9.8386236013597248	0.0026247581412620	0.1976567289175268	-0.0886171560059473	0.1263385861607927	
+3.7389999999999999	0.0394020511336388	9.8229194389362000	0.0292631497189566	0.2808134380294846	0.0463941659682957	-0.0900088208775738	
+3.7399999999999998	0.0783874364878684	9.8208256761625368	0.0204059069151992	0.2343582220694424	-0.0999353537928582	0.2325429936238962	
+3.7409999999999997	0.0548074159799663	9.8063449720898745	0.0137444216791347	0.0776782395275759	0.0268766879150403	0.1385418509231892	
+3.7420000000000000	0.0451799802156192	9.8050568429128795	0.0323770821794590	-0.1245896991195509	0.0882065404307671	0.2670326397866133	
+3.7429999999999999	0.0394478049757261	9.8105838650939212	0.0468072515441638	-0.1732444988573311	0.0623135035358832	0.1243064858190290	
+3.7439999999999998	0.0609730659634307	9.8258855679655177	0.0179423125027910	-0.0029507407054878	-0.0664700185619468	0.3965390579926343	
+3.7449999999999997	0.0595086065224101	9.7991468440605036	0.0036084945897139	-0.1330390638059830	0.0004850808921803	-0.1414017056466995	
+3.7460000000000000	0.0336218128150890	9.8476445035081941	-0.0028100197793094	0.2294324054286709	-0.1903353224455185	0.1304904519197985	
+3.7469999999999999	0.0583963749577753	9.8397780741010390	0.0219676685518710	0.0684863966439146	0.0037469485455688	0.3811497450744230	
+3.7479999999999998	0.0433864109730961	9.8207342398599664	0.0112223009412392	0.1780023852561335	0.0275857501100319	0.2424217305006502	
+3.7489999999999997	0.0562214358580037	9.8282975809580204	0.0093855787158806	0.0384203538444166	-0.1022163395007068	0.0959539669081944	
+3.7500000000000000	0.0423538083265983	9.8146356600661022	0.0294760846376998	0.1153906929604113	0.1243301764605813	-0.2491074169365990	
+3.7509999999999999	0.0386023760952142	9.8408191653066037	0.0386007678396431	-0.2297517363936041	0.0198909379145713	0.1950612276025529	
+3.7519999999999998	0.0556396649246899	9.8235971888363363	0.0225449313536423	0.0483963526783174	-0.0240026245550097	0.0412642353660711	
+3.7529999999999997	0.0498001436144885	9.8138764923345736	0.0081815631983953	-0.2807183563374557	-0.2634449443570721	0.2170620247565094	
+3.7540000000000000	0.0497604286230353	9.8175157280870398	0.0287578409380285	-0.1267986381424965	0.2461707553075889	-0.1093165734490970	
+3.7549999999999999	0.0584898203354798	9.8227965180002883	0.0221885680376315	0.1026193700633480	0.0578131637932641	-0.1294512257162441	
+3.7559999999999998	0.0401913409532072	9.8164111120969544	0.0189072420480977	-0.0255035746124935	-0.0873902691842349	0.0398270645071341	
+3.7569999999999997	0.0536436784255528	9.8218472707995712	0.0180397206284701	-0.1471780274841786	-0.0353598098476473	0.2678291044886977	
+3.7580000000000000	0.0661186999119202	9.8231877402170547	0.0132752183465419	-0.0059971607796781	0.1523966319927590	0.0661058774435410	
+3.7589999999999999	0.0664657655767271	9.8184123765645985	0.0332344631614936	0.0040157422770912	-0.0392949545491819	0.2481857823301661	
+3.7599999999999998	0.0710662739614536	9.8333691570481658	0.0183525453800915	0.1611824649642545	0.1194943598579476	0.0448957037971457	
+3.7609999999999997	0.0576904338269979	9.8258571792471390	0.0194765777043446	-0.0504834464616679	0.1428447901477058	0.0546069181474918	
+3.7620000000000000	0.0412610011471376	9.8074533059586013	0.0163919903887036	0.0921908842431218	-0.0205321978987924	0.0934308657788036	
+3.7629999999999999	0.0614557645872745	9.8224697368568936	0.0052167988208181	0.2081312080627204	-0.0714274890383302	0.2249679047383597	
+3.7639999999999998	0.0759133796808172	9.8147454486020447	0.0101698658427344	0.2854772045912809	-0.1829111891645089	0.1281383907060576	
+3.7649999999999997	0.0650276789859855	9.8101762881662804	0.0388656113970073	0.0406736275298286	-0.2095552800630774	0.1595426000990993	
+3.7660000000000000	0.0777059666234218	9.8429375270183304	0.0127264014373073	0.0430581168622145	0.0299323565662966	0.1763220228282779	
+3.7669999999999999	0.0723730303018082	9.8194928055492134	0.0065318751792280	-0.0705848566006576	-0.0594312250713790	0.2498234129636473	
+3.7679999999999998	0.0480724061369061	9.8268374005542949	0.0171190893446849	-0.0301942566306185	-0.0061718503784819	-0.1637851957079482	
+3.7689999999999997	0.0532085118307063	9.8272420879274041	0.0247078546700053	0.0036969417959733	-0.0058235382548595	0.2340535650423712	
+3.7700000000000000	0.0367787086167946	9.8126262756095013	0.0328807029342636	-0.0595012510742011	0.0801489787520601	0.3782455750386234	
+3.7709999999999999	0.0491714819692363	9.8273813582109923	0.0077017105606755	-0.0862032456040576	0.0173792382796369	-0.0422069936151719	
+3.7719999999999998	0.0406538991994628	9.8370451525264944	0.0123021328067160	0.0507867924252860	0.0897800537453052	0.0443505630181666	
+3.7729999999999997	0.0639796171365507	9.8302441470184370	0.0290370106566989	0.1008160743214717	-0.0396364397346294	0.0526976911780360	
+3.7740000000000000	0.0678279761744376	9.8313470234380596	0.0423889703461593	0.0103123805007967	-0.2265095322903521	0.0301103421677594	
+3.7749999999999999	0.0690242046534984	9.8246187778806302	0.0357355356274870	-0.1225525277769230	-0.2136745274391493	0.1275558621159334	
+3.7759999999999998	0.0628785802136422	9.7837626232692845	0.0094734336545116	-0.1439660005221872	-0.1150858577821710	0.2704900273577575	
+3.7769999999999997	0.0482640423000657	9.8306911647260140	0.0109818868358972	0.0080063245248249	0.0540349107352950	0.2532515251619092	
+3.7780000000000000	0.0571992830710942	9.8340511980220651	0.0130304405307475	-0.0917274452543332	-0.0530329049327655	0.1089836501512044	
+3.7789999999999999	0.0617864552682819	9.8568236315731355	0.0311043059681909	0.0637326626477799	-0.1077238139359661	0.3688164449910717	
+3.7799999999999998	0.0430703190316382	9.8360297556281324	0.0226784281488146	0.1931723150326992	-0.1590913690579014	-0.1733249066843801	
+3.7809999999999997	0.0445996138585788	9.8284969390056460	-0.0005282557495412	-0.0110428241059026	-0.2536094556705390	0.1386238149897296	
+3.7820000000000000	0.0587297449495826	9.8271715191609506	0.0254807831175566	0.0263717871635923	0.0418820987339294	0.0334199269239260	
+3.7829999999999999	0.0342291098754649	9.8047564801742446	0.0375401102135011	0.1174479757199885	-0.2558871363020744	0.1719803791732450	
+3.7839999999999998	0.0604314412127322	9.8435645791880013	0.0287411908436533	-0.0148659589153842	0.1945647188638810	-0.0217834962459132	
+3.7849999999999997	0.0591984549356051	9.8311107213209770	0.0200095506278178	0.3705622808759303	0.1035097917505841	0.3309016846998089	
+3.7860000000000000	0.0320766080971813	9.8209218207684135	0.0142448177341655	0.1327068795077936	-0.2505977106580642	0.1636833712306392	
+3.7869999999999999	0.0579933435376051	9.8155153403960309	0.0223158110809979	-0.0635479504641535	0.0593433251903093	0.1624970267887347	
+3.7879999999999998	0.0513714950704378	9.8132153580911083	0.0448403441381386	-0.1811525531103143	0.1196504461188852	-0.0236967421768073	
+3.7889999999999997	0.0492553704396496	9.7951434875941032	0.0454368010893814	-0.0448576364802044	-0.3226928408000097	-0.0615389306128802	
+3.7900000000000000	0.0500027904261958	9.8290984260100007	0.0065154773922850	0.1652428857991891	0.2167464684289989	0.1186698612694227	
+3.7909999999999999	0.0527189130212484	9.8461187535851522	0.0053866086618150	-0.1240086224304032	-0.0445737980411189	0.2720103516400624	
+3.7919999999999998	0.0863756561485226	9.8265035884767258	0.0077535185440478	-0.0483908682876950	-0.1769841733284193	-0.1534664192788867	
+3.7929999999999997	0.0669529864344173	9.8311542162273664	0.0343604758803814	-0.0589267214401786	-0.2012996894374886	0.0729491356564389	
+3.7940000000000000	0.0602998252560105	9.8400955464625071	0.0289211740588415	0.1308684277004148	-0.1907954355549865	0.3238597708937859	
+3.7949999999999999	0.0672995130076736	9.8231922249176424	0.0193177560006046	0.1242089650223459	-0.0899531363540372	-0.0871623585465591	
+3.7959999999999998	0.0368673045162161	9.8097152713543103	0.0266766746278380	-0.0330432591163142	0.1836438653567225	0.1761969087788933	
+3.7969999999999997	0.0342008491518944	9.8194810868506437	0.0196175342903194	-0.0168561114082232	0.0262998731296591	0.2870823272221287	
+3.7980000000000000	0.0330064064517435	9.8170611924144922	0.0405581717768426	0.0601531647366394	-0.2616752517881602	0.0772993386580894	
+3.7989999999999999	0.0423011275384834	9.8271953470385665	0.0044415762876463	0.1748553938006984	-0.0915612901317907	0.0048984327535989	
+3.7999999999999998	0.0345518477226818	9.8351540680468776	0.0265998858790788	-0.1044873365618116	-0.1699120394292252	-0.0173910931528210	
+3.8009999999999997	0.0606510204424310	9.8215660701192693	0.0127576964641424	-0.3692694924251936	0.2153088265883185	0.0194702195996609	
+3.8020000000000000	0.0441656465815043	9.8314413414021633	0.0175232965909194	-0.0363103731977605	-0.1573517683690227	0.0585787393827745	
+3.8029999999999999	0.0601919524297021	9.8046337661418583	0.0201128303383429	-0.1083851394266509	0.1013338725487047	-0.0761706856639042	
+3.8039999999999998	0.0797197741208262	9.8162879799514098	0.0101380249927469	-0.0055639967902599	-0.1272917934720627	0.0178874620048248	
+3.8049999999999997	0.0731191017876535	9.8183848943308263	0.0090828126258586	0.0840649539803682	0.1583983110008134	-0.1126718774832429	
+3.8060000000000000	0.0674622743369277	9.8146267081661609	0.0241499738754436	-0.0223114694041908	-0.1388103427149995	0.0857729262635009	
+3.8069999999999999	0.0583583199840169	9.8147530976768547	0.0259277265130122	0.0805431399767930	0.1147710143739304	0.4186855806763906	
+3.8079999999999998	0.0420139757986473	9.8209014842788616	0.0216366793652407	-0.1368381758691784	0.1759762590263572	-0.0184977341851630	
+3.8089999999999997	0.0532661667434976	9.8262436522148047	0.0315747338169107	0.0298201057923184	0.0145559377802317	-0.0149169286833526	
+3.8100000000000001	0.0523514574591015	9.8191954309821181	0.0377287152889298	0.2093939498124719	-0.0109036194118074	0.2751119680527443	
+3.8109999999999999	0.0424198979239773	9.8396080070723162	0.0164219768969326	0.2451450740906458	0.1839638383855361	0.3315623889997711	
+3.8119999999999998	0.0332515633995659	9.8248378190310408	0.0423166486704176	-0.0125716998794079	0.1533607068664437	0.4413033136018092	
+3.8129999999999997	0.0744881660780363	9.8094357389945461	0.0311708364963740	0.1860710963009037	0.1879437048734523	-0.0411161205933674	
+3.8140000000000001	0.0481138875572338	9.8210069651424678	0.0224941643329408	-0.0678606391103705	-0.2398384318934358	0.1447145256995828	
+3.8149999999999999	0.0470861454646176	9.8417795146388478	0.0334908851449172	0.1966916462033239	0.0261979940392627	-0.1146321409385162	
+3.8159999999999998	0.0570232415271767	9.8138051434352427	0.0225002122135683	0.0865401645456415	-0.0177286400948392	-0.2019138741886363	
+3.8169999999999997	0.0561561056781693	9.8346505819709922	0.0093111402387849	-0.0383476198972818	-0.1056970989622086	-0.0039930831126369	
+3.8180000000000001	0.0648699789014807	9.8144711772519777	0.0056536933814258	0.1701685205169228	-0.0741945735777967	0.1184146935851696	
+3.8190000000000000	0.0732553265662260	9.8222842705776987	0.0230450376896789	0.2249081291907496	-0.1675451284150933	0.1830298818771759	
+3.8199999999999998	0.0376838879172405	9.7988257559578056	0.0272465162201111	-0.0915122191364773	0.1190884968861005	0.1180220269828588	
+3.8209999999999997	0.0580431606551340	9.8432204067803042	0.0209828736260673	-0.1074584591673200	0.0992520286679020	0.0809456940519492	
+3.8220000000000001	0.0548534377955360	9.8214416246552609	0.0325314688418304	0.0216345455268422	0.1987504927769927	0.1903785775480274	
+3.8230000000000000	0.0570543754047742	9.8304531619508246	0.0378412206857644	0.0585577001396825	-0.2863528433703584	0.0359372307115198	
+3.8239999999999998	0.0343135875842494	9.8159925357846411	0.0191410297401289	0.3056067959426217	0.0098670774265330	-0.1278131749397685	
+3.8249999999999997	0.0580820081974598	9.8451135094391837	0.0123356710758555	0.0012034823231808	0.1244745635205078	0.1252948462509519	
+3.8260000000000001	0.0391356898142814	9.8293230230446778	0.0304680257821881	0.0578532832310885	-0.1978457841188742	0.0665143494911989	
+3.8270000000000000	0.0568276276272192	9.8059740877036905	0.0221538660072585	0.1001610687852272	-0.0010862407681168	0.2768357663836998	
+3.8279999999999998	0.0622925173433971	9.8206122073669135	-0.0000307098991425	0.2474128338361060	-0.1889170944054814	0.2107122188470477	
+3.8289999999999997	0.0553777734397812	9.8115299314392956	0.0256920606679886	-0.0613846512809288	-0.1780409276685071	0.1045042597702635	
+3.8299999999999996	0.0627478811193540	9.8109803561137010	-0.0041278861053037	-0.2630127067327016	0.0602569726577010	0.1190790509834451	
+3.8310000000000000	0.0586223527835170	9.8400869655290837	0.0263354364145333	0.0021738663439725	0.1909872971479705	0.0748914489450924	
+3.8319999999999999	0.0551324558141296	9.8231446989593980	0.0217005911478321	0.0866579970441503	-0.2411982347721437	0.1874639450066448	
+3.8329999999999997	0.0579152734319223	9.8200156919313280	0.0054564994327946	0.2395158622356379	-0.0976747633382700	0.2161729339853433	
+3.8339999999999996	0.0547677360529243	9.8265784530087217	0.0143033143062831	-0.2759362825569338	-0.1817901486665228	-0.1229219773959833	
+3.8350000000000000	0.0413492738314062	9.8057289361164646	0.0399134641476536	0.0109367811359243	-0.1495016803771563	0.0824819919210296	
+3.8359999999999999	0.0317875355028841	9.8381538684684156	0.0291967425052582	0.2298620447065674	0.0255354084221315	-0.0028060496145274	
+3.8369999999999997	0.0596307459599345	9.8155531557214921	0.0070954811924072	-0.0900170244208244	-0.1553055596889986	-0.1709648878017228	
+3.8379999999999996	0.0614469364179494	9.8149281073177779	0.0004629462569584	-0.1854780377548918	-0.0998629323258759	-0.0673773443897862	
+3.8390000000000000	0.0409943827652253	9.8192181076228717	0.0116266088628288	0.2066742133809182	0.1446051267922742	0.1712889906445580	
+3.8399999999999999	0.0421220127302061	9.8382649866701843	0.0238210593025009	0.1222904773810689	-0.3455067214349882	0.2016610846937248	
+3.8409999999999997	0.0657996627226888	9.8108450015589082	0.0172808968724056	0.1875123489920527	-0.1546068409449506	0.0531244494830877	
+3.8419999999999996	0.0582998270701933	9.8242296534097875	0.0141524091740030	0.0496621550335130	-0.2180032480074383	-0.0795984402242569	
+3.8430000000000000	0.0633789714602787	9.8273996471236273	0.0290074440309321	0.0418903991421825	-0.3446494383054588	0.1388502674794926	
+3.8439999999999999	0.0564574281368814	9.8294245849504662	0.0298062769062876	-0.0174772026586115	-0.0799850937306542	0.0830527796271835	
+3.8449999999999998	0.0531905892557472	9.8215831903218795	-0.0010452260874547	0.1549013515362548	0.0186038743497348	0.5608491186934259	
+3.8459999999999996	0.0352689437784853	9.7854581354753023	0.0117522916012063	0.1444639504547791	0.2336521406014901	0.2235906542374679	
+3.8470000000000000	0.0394015776096104	9.8416842834569032	-0.0059632440169093	0.4987346904764879	-0.0518446482447799	0.1128683902634196	
+3.8479999999999999	0.0495399343245624	9.8312431817743597	0.0164438022647868	0.1536227107171120	-0.2050883671360904	0.0887930649504749	
+3.8489999999999998	0.0558901634800858	9.8210513573420020	0.0205797611794551	-0.1542007488926389	-0.2139999858486374	0.2185373586204835	
+3.8499999999999996	0.0515152954057867	9.8059350195572161	0.0137914828340423	0.3653567283754601	-0.2631533537487873	-0.1717306449002579	
+3.8510000000000000	0.0600609639426729	9.8175780077390833	0.0214767561490565	-0.0262620867372387	0.1102172752687887	-0.0008276725332273	
+3.8519999999999999	0.0393296762151113	9.8161667720699093	0.0031046339780255	0.0614036881291734	0.0308915708249207	0.1724057614579819	
+3.8529999999999998	0.0582739227633175	9.8194023154095778	0.0238275001541050	0.1322793596852538	0.0560561506059604	-0.1734741918599397	
+3.8539999999999996	0.0658082370526128	9.8277520242555312	0.0011520106633701	0.1974096148535835	0.0726130261154833	0.1100288553666675	
+3.8550000000000000	0.0522967538548154	9.8165600173547851	0.0038361160963085	0.1344809702968889	0.0408773625265990	0.0527030709169354	
+3.8559999999999999	0.0563306054624328	9.8210511942931955	0.0434600821671377	0.0825111438451510	-0.1754021740014124	0.1015896072949999	
+3.8569999999999998	0.0394109562228413	9.8270726703989375	0.0147487874829213	-0.1459603333541860	-0.1294016919577597	-0.0294265582080949	
+3.8579999999999997	0.0666863024397749	9.8236267009894807	0.0096729557454320	0.2819962818427661	-0.0843723527968948	-0.1734638216876295	
+3.8590000000000000	0.0479119297763724	9.8233258345936694	0.0226725215797194	-0.1880059111454702	0.0201501427376367	-0.0941481812611356	
+3.8599999999999999	0.0627510773653709	9.8305717791747149	0.0045305933632570	0.0795067056319216	-0.1821105258592967	0.0149264235429878	
+3.8609999999999998	0.0546892688334640	9.8143801774429971	0.0246617773293395	-0.0085151739007437	0.0335482077981532	0.0501752660712408	
+3.8619999999999997	0.0649476673429321	9.8351551051552146	0.0155099196684683	0.2998312339124145	0.2364740986124800	-0.1649572972264866	
+3.8630000000000000	0.0697354885961125	9.8227047475202856	0.0136110117134225	0.0926677722157273	0.0856439504013126	0.0668332664760744	
+3.8639999999999999	0.0614932088119311	9.8296447495421475	0.0283975427768902	0.0583886650578123	-0.0939883888472287	0.1082671347451689	
+3.8649999999999998	0.0843937824218216	9.8135203031983966	0.0199559388464780	0.2320246724969819	0.2383352287991042	-0.1252980409645216	
+3.8659999999999997	0.0638258691742576	9.8375460503958987	0.0284195821502636	0.2020446944603040	-0.0955767222912091	-0.1417227453917919	
+3.8670000000000000	0.0504030157276856	9.8127822580052566	0.0364360205680387	-0.1653008751125117	-0.0919299639759449	0.1116563622333680	
+3.8679999999999999	0.0642796353966703	9.8105125614494764	0.0254578819602895	0.1808589079576091	0.0393622938959136	-0.1375155505839096	
+3.8689999999999998	0.0533991587009027	9.8323892050343566	0.0315674554930371	0.2226930398579808	-0.1141388043037468	-0.0730611613823188	
+3.8699999999999997	0.0452554273461041	9.8148802620515099	0.0548105465416861	-0.2250985606422346	-0.4388360316502373	-0.2031016397305385	
+3.8710000000000000	0.0473406856302790	9.8091046408439055	0.0295631985312379	-0.1965331872330102	0.1796330618937227	-0.0897227031323856	
+3.8719999999999999	0.0643088105309765	9.8407457012748321	-0.0019962758244551	-0.3347122921537340	0.4011927710287586	0.1318923701083990	
+3.8729999999999998	0.0658029376594468	9.8206304630508221	-0.0051947906272447	0.0195089749504420	-0.2235736448978241	0.1925013692962725	
+3.8739999999999997	0.0569066120128861	9.8028043145421577	0.0315654059064041	0.1127847242215477	-0.3161647220381572	0.1989375270810042	
+3.8750000000000000	0.0552748885979642	9.8270052882549805	0.0160708160619138	0.1375525982702950	0.0633987418354127	0.1606054960284287	
+3.8759999999999999	0.0486584155345354	9.8364710918571099	0.0090449790230471	-0.1362754930520458	-0.0786378843705324	0.1114241671357337	
+3.8769999999999998	0.0389955398036131	9.8024670669879406	0.0241371370523336	-0.0104124603115322	-0.0116770885532035	0.2241960723440455	
+3.8779999999999997	0.0307833861610606	9.8265352419499248	0.0091740171257535	0.1045001349644776	-0.1246428827479370	0.1420703866182845	
+3.8790000000000000	0.0587518747349150	9.8149457481951945	0.0316801203559331	0.1093076967534120	-0.1129763701909741	-0.1572936820314818	
+3.8799999999999999	0.0594127425442534	9.8237786355866223	0.0287128791330923	0.0297091365749837	0.2066790587628595	-0.0923594261567477	
+3.8809999999999998	0.0310958385197666	9.8357956421147055	-0.0084713863958269	-0.1263823749698308	-0.0242177070170335	0.0900622806708779	
+3.8819999999999997	0.0440208398393750	9.8394180995365943	0.0280740483616404	0.1042600853512218	-0.1922828251344365	-0.1948626452454423	
+3.8830000000000000	0.0506632579409743	9.8264849735727804	0.0164352764192305	0.0809501924350321	0.0089629542515194	0.3285261470448552	
+3.8839999999999999	0.0688095764945804	9.8324555086709822	0.0239445033456101	-0.2011686841632786	-0.0878468150323445	0.1590894451709239	
+3.8849999999999998	0.0711989401790544	9.8312234430461487	0.0024956279503418	0.0432630441705572	-0.0114355273101561	-0.2239418394274640	
+3.8859999999999997	0.0494841785878711	9.8298188739774766	0.0541589188142470	0.1242850067657691	-0.0472915542193099	0.1060016248692755	
+3.8870000000000000	0.0698281793463361	9.8111831156706639	0.0141886048559101	-0.0630317353827600	0.0556142845473813	-0.0072289882948249	
+3.8879999999999999	0.0405473654811021	9.8297272736354682	0.0053672430467846	0.1591441374103732	-0.0839420186638468	0.0313410253045532	
+3.8889999999999998	0.0549612768339056	9.8034762960923292	0.0202035700248274	-0.0611943756411882	-0.3250369320704126	-0.0444484052673593	
+3.8899999999999997	0.0392612156256966	9.8156343471042735	0.0329247285466263	-0.2136581489477093	0.1002831285633361	0.2064792232275732	
+3.8910000000000000	0.0358157712141586	9.8317648341527004	0.0126860557403013	0.1307136582983507	-0.3202866054940962	0.2090733452660671	
+3.8919999999999999	0.0606595279902767	9.8254196098185904	0.0231362371843032	0.0008354080836681	-0.0683297568561796	-0.0918469510529191	
+3.8929999999999998	0.0606339281838091	9.8030860019249815	0.0004820045975166	-0.0078479058999177	-0.0474415336464526	0.2645929353807490	
+3.8939999999999997	0.0468517513903692	9.8238010341395814	0.0134675246102991	-0.0827672157482680	-0.0193089311661478	0.1259935117060854	
+3.8950000000000000	0.0468655364517421	9.8256990295005071	0.0202849690726616	-0.2648219448572736	0.0905204776114716	0.2024060412940660	
+3.8959999999999999	0.0549326221328317	9.8132349132638819	0.0256400056661669	0.1738897217823699	0.1347959231592790	-0.0905531466107759	
+3.8969999999999998	0.0713971930958186	9.8307705738099056	0.0204758924578221	0.0738681300560467	-0.0430207245751364	0.0710856624944371	
+3.8979999999999997	0.0677101939378315	9.8283271842942082	-0.0078941694077572	0.2818073901268726	0.0784341112789964	-0.0617509960850885	
+3.8990000000000000	0.0449576885914520	9.8202767692287463	0.0163146028573258	0.0453357033448819	-0.1443346629716614	0.1182741776543408	
+3.8999999999999999	0.0736018773569614	9.8367472464645296	0.0215503849789776	-0.2586308075812621	-0.2199973411095038	0.2098615462951955	
+3.9009999999999998	0.0499058926595900	9.8217477295445708	0.0189610724837503	-0.2795333128747823	-0.1761373413876480	-0.1782058069648329	
+3.9019999999999997	0.0597039995466512	9.8067620562753497	0.0077782316924654	0.4066945175308446	0.2016918981501458	-0.0529056046888432	
+3.9030000000000000	0.0690181024377430	9.8171808006395427	0.0121453940741911	0.1533758871048617	-0.2174910427460507	0.0826839341923462	
+3.9039999999999999	0.0626266350095003	9.8178070329610492	-0.0039298131556193	0.0919591277786097	0.2391504791882589	0.0213909610340920	
+3.9049999999999998	0.0353727417691986	9.8311260757459760	0.0305813442852439	-0.0230190578881160	-0.1314067453337231	0.0236504340887868	
+3.9059999999999997	0.0608568705476211	9.8158804859780364	0.0200056557398493	-0.2775580867709130	0.0390798990707370	-0.0111847590352488	
+3.9070000000000000	0.0445228775833010	9.8280623876385000	0.0125726558294520	0.0228138015320559	-0.0087252009419946	0.2629561398183573	
+3.9079999999999999	0.0442004935154077	9.8171744924202091	0.0202337022264971	0.0412464012775266	0.0225633845798698	0.0843906420657121	
+3.9089999999999998	0.0482646625512479	9.8092942465418176	0.0241796182706368	0.4385871691684904	0.2686324202710121	-0.0572523078633679	
+3.9099999999999997	0.0558706249507756	9.8222644958535721	0.0161210323475579	0.1351909114947518	0.0437730976761102	0.1365681785913110	
+3.9110000000000000	0.0484330015925361	9.8312981550136929	0.0473194701161752	0.0362847440005197	-0.0683976038724852	0.0121585535054638	
+3.9119999999999999	0.0552733043907421	9.8220043533766646	0.0300547721716312	-0.0420713197405786	0.0043964347767244	0.2759209913684880	
+3.9129999999999998	0.0315424262989581	9.8142399010409491	-0.0056167687780139	0.1669557861878467	-0.0275109692233087	0.1324971166258986	
+3.9139999999999997	0.0475945198279655	9.8159375719366935	0.0043231914641720	0.2031416186050803	-0.1046869905679007	-0.3259401629957375	
+3.9150000000000000	0.0593968359492435	9.8156594987304793	0.0090768430996486	0.0613670445646855	0.1051722938503624	-0.0213836839398054	
+3.9159999999999999	0.0521374646672355	9.8137707519284305	0.0240675798981910	0.2503776827317340	0.0251097677309717	0.1510368653043386	
+3.9169999999999998	0.0515463541886687	9.8307745147327470	0.0066975652215994	-0.1711108382086303	0.1223997087451738	-0.0035676632039755	
+3.9179999999999997	0.0468183814108301	9.8385885149313932	-0.0008746287757724	0.0425169664866709	0.1464231165536557	0.2080192477903500	
+3.9190000000000000	0.0543274897469962	9.8211866924886735	0.0253720575982463	0.1223078537978954	0.2598753106085583	0.1580861789979950	
+3.9199999999999999	0.0436120078210060	9.8242819129939285	0.0450757150502617	0.0711340627327977	0.0748024544461510	0.0092629563164195	
+3.9209999999999998	0.0454663888568641	9.8190426576291276	0.0273539058515507	0.3514965107613901	-0.2691435702755820	0.0223072028163743	
+3.9219999999999997	0.0624313224179360	9.8233004788965985	0.0102450909684308	-0.1771659319968578	0.2465265994277525	0.0961583733792396	
+3.9230000000000000	0.0582283180251725	9.8176831600632752	0.0257924529421903	0.1614590637590083	0.0612771545604443	0.0855432836747138	
+3.9239999999999999	0.0599660798727945	9.8286884194882997	0.0340999673669398	0.1051979894839172	0.0404483757445144	-0.1222615496532930	
+3.9249999999999998	0.0575946966115763	9.8237299645402612	0.0214490343374887	-0.0360389308768335	-0.2290087553469975	0.0658343160587163	
+3.9259999999999997	0.0560135835014832	9.8299479198523549	0.0031853133060203	0.0086222039497966	-0.0483070679431136	0.1952164392866463	
+3.9270000000000000	0.0741387046471317	9.8050069857557407	0.0240512277077969	-0.2283016069673834	0.0325571232443599	0.1500036157047845	
+3.9279999999999999	0.0719996113789580	9.8327107803192302	0.0072272703459587	0.0222955982562126	-0.0306156603775195	-0.2222450892043951	
+3.9289999999999998	0.0560870064727102	9.8254646737250368	0.0382450665185911	0.0553394699154188	0.0152005123036631	0.1029257718266457	
+3.9299999999999997	0.0588833078625789	9.8282063533478290	0.0233368284486445	-0.1065477771249562	-0.0771582380340685	-0.1394021254462831	
+3.9310000000000000	0.0591372889247560	9.8044762068288112	0.0123646110511165	-0.1387640505245685	0.0748027451158349	0.1131500157052068	
+3.9319999999999999	0.0526965284878819	9.8327013351938781	0.0062331475872425	0.0479148514631315	0.0064259234777314	0.0968402532657485	
+3.9329999999999998	0.0452221469141489	9.8368796582467439	0.0242987123737556	0.2800536745239801	-0.0659466044731555	-0.0668849626862190	
+3.9339999999999997	0.0572160886244167	9.8200413751224911	0.0512028437582312	0.1348420678052610	-0.0553746912438214	0.0973388267424814	
+3.9350000000000001	0.0680170340308562	9.8088512115865409	0.0202467806512399	-0.0960340171433198	-0.2047915895839851	-0.0734885038440106	
+3.9359999999999999	0.0583034326469932	9.7865234835917025	0.0135904849776642	0.0970757237472106	-0.0332916364551477	-0.0555547244248516	
+3.9369999999999998	0.0604857237981625	9.8231650339001106	0.0200011355875547	0.0765929999680179	0.0042210357410761	0.1527472328016593	
+3.9379999999999997	0.0558758834068102	9.8242383528486403	0.0296167958662592	0.4196979550031110	0.0174248148137356	-0.0035039885105962	
+3.9390000000000001	0.0629198887339604	9.8184644129571002	0.0144734242514195	0.0134411960388907	0.1135683125376232	0.1697371819237848	
+3.9399999999999999	0.0642074115868691	9.8223952795939802	0.0225620316799886	-0.0055995285787540	0.0689727572304983	0.1494778457608454	
+3.9409999999999998	0.0413361978276795	9.8263077004135901	0.0504888543896861	0.0916873354431068	0.0676517559126865	0.1164230201309045	
+3.9419999999999997	0.0544050057591143	9.8240719443110383	0.0383235698333335	-0.0605985372745917	0.0329120277703724	0.1820095762202986	
+3.9430000000000001	0.0433417812441123	9.8254658694940957	0.0262797231125864	0.1166440174578944	-0.0602971585633029	0.1375496174325310	
+3.9440000000000000	0.0588832470570521	9.8181395734153973	0.0037416516647466	0.3449370630194052	0.0399778937800496	0.1705896466421528	
+3.9449999999999998	0.0409918133346325	9.8142209361628527	0.0189386831214483	-0.0900152039172813	-0.0968280344262259	-0.1415667034166396	
+3.9459999999999997	0.0595411804535445	9.8217535589200740	0.0302805639086060	-0.3214444863713593	-0.0175535634699927	0.0985818226004991	
+3.9470000000000001	0.0622811900760859	9.8088042533655795	0.0204784081094824	0.0063623485549217	0.0243638865862632	0.2719816775692116	
+3.9480000000000000	0.0728736258587574	9.8134576773455962	0.0187110595670213	0.0386761036563284	-0.1163707079177832	0.0598389034259015	
+3.9489999999999998	0.0645484424571538	9.8454525520606637	0.0276446481315427	0.2304086117645940	0.1554103297776718	0.2541959349109943	
+3.9499999999999997	0.0562902947403433	9.8338424370528656	0.0293416145934072	0.0130674895589964	-0.1096088405503207	-0.0614344517965426	
+3.9510000000000001	0.0795469456132007	9.8130072478604582	0.0172919653640665	0.0915895756206731	-0.2475412295803859	0.1225087009391451	
+3.9520000000000000	0.0644687119273743	9.8065929189934895	0.0206931886112193	-0.0113935498531161	0.0116471436309754	-0.0588173961225805	
+3.9529999999999998	0.0585975441392171	9.8188327153941106	0.0200404855475185	0.0744883371987713	-0.0659791145037489	-0.0137731271004288	
+3.9539999999999997	0.0532010363209630	9.8169366008146675	0.0106428735491981	-0.2376434974537154	-0.0533038923931652	0.2152741703361116	
+3.9550000000000001	0.0579623162258185	9.7971146836817589	0.0127140085004975	0.1289126130955422	0.0068248700427810	0.2388567319688870	
+3.9560000000000000	0.0533194804670223	9.8265949329376241	0.0179329291137527	-0.1031205947787595	0.0626636619606411	0.1239599915158866	
+3.9569999999999999	0.0670545946477697	9.8130372513114299	0.0438961168159490	0.0800576064433563	-0.4255087021717474	0.1747320039827208	
+3.9579999999999997	0.0345508016667650	9.8130788371669109	0.0047155845033967	0.1658326058898113	0.0258521182201705	-0.0568843423792495	
+3.9589999999999996	0.0534717498656305	9.8333352514276129	0.0047368505149927	-0.0690528247396949	0.0753006440141550	-0.0639834434518750	
+3.9600000000000000	0.0592473837232179	9.8247901221185838	0.0136544718634020	0.0514240563885120	-0.0748536392690435	-0.2868644990256636	
+3.9609999999999999	0.0546645656228098	9.8227713695626964	0.0299756101329661	0.2548318290978120	-0.0834956178051819	-0.0834641649470164	
+3.9619999999999997	0.0597126866071082	9.8239045887726082	0.0130678950850137	-0.0274972745499754	0.0709021075232121	-0.1134805341282974	
+3.9629999999999996	0.0512536205914661	9.8174468487830691	0.0049448521021729	-0.0804686439191196	-0.0221702845767205	0.2540265157673532	
+3.9640000000000000	0.0549766836235843	9.8145589974424059	0.0147962790695042	-0.0500562744574837	-0.1419583598975918	-0.1174374733563759	
+3.9649999999999999	0.0643897331887810	9.8162318799412187	0.0195841798651083	0.1934148802258877	-0.1116711440500459	0.2715390412454648	
+3.9659999999999997	0.0571811686207550	9.8386577127048511	0.0018201769202233	0.1374309402694786	0.0104349436537475	-0.1098183710492926	
+3.9669999999999996	0.0615027080912415	9.8196128113253529	0.0165038283276859	-0.0090560942146278	-0.0920502023095017	0.1865310662316675	
+3.9680000000000000	0.0609586913678678	9.8212917373017632	0.0120861976423405	-0.0701528973214361	-0.0240588820569558	0.2948018406413220	
+3.9689999999999999	0.0444841936904060	9.8176937137236546	0.0273285193963101	0.0105579011500861	-0.0366917619295122	0.0010202277043616	
+3.9699999999999998	0.0771367789216754	9.8140074658944538	0.0172225815825110	-0.0457968048598285	0.0697237298194912	0.0581511666500585	
+3.9709999999999996	0.0609726016443586	9.8140218601318985	0.0362291437664251	0.0078785230695785	0.0641423735179296	0.2015176648114384	
+3.9720000000000000	0.0585370130329730	9.8091062222353127	0.0305147218563859	0.0065544487941463	-0.3058361796445583	-0.1807510148957441	
+3.9729999999999999	0.0721638468267236	9.8405904801114268	0.0122670886322851	-0.1232051444969789	-0.1032823444238499	0.2113221879936050	
+3.9739999999999998	0.0404760315334519	9.8269585240192860	0.0219206280361342	0.0660389958340713	0.0293465970709286	0.1283423499648860	
+3.9749999999999996	0.0601949454462825	9.8222052802353836	0.0248220562462137	0.0605724015730443	0.1708654594041545	-0.0899214024632951	
+3.9760000000000000	0.0612533624634614	9.8068918596839474	0.0189174843949082	0.1534017132689853	-0.0604695474838801	-0.1089486717013700	
+3.9769999999999999	0.0461959693455720	9.8186727967923222	0.0016983539853550	-0.0803566648668812	-0.0704537213568822	-0.0127034854764363	
+3.9779999999999998	0.0782965773474498	9.8312475697200163	0.0181664378417730	-0.0012104735211043	0.2810484080346476	0.1155848530712077	
+3.9789999999999996	0.0671863343997021	9.8228157964841305	0.0378799667002886	0.0218824411912470	0.0233422514599840	0.0575308932590385	
+3.9800000000000000	0.0390515683696938	9.8277915136491050	0.0304013450063535	0.0186436600686299	0.0419120655065203	0.0698265619977757	
+3.9809999999999999	0.0555630018492205	9.8226862280055691	0.0225164151310099	-0.1491827107164167	0.0237686686094930	0.3695001319357805	
+3.9819999999999998	0.0595943590265260	9.8124804794558536	0.0266113059514611	0.1126846981973963	-0.0603138801189918	0.3764443227465075	
+3.9829999999999997	0.0588641786386020	9.8282272310255809	0.0094866866277312	-0.0491283941824408	-0.1441350386031942	-0.0984945780293330	
+3.9840000000000000	0.0426796970140636	9.8105939538196463	-0.0054825690989081	0.1474165675044051	-0.0111648912738030	0.1633263524249564	
+3.9849999999999999	0.0552122575288922	9.7963395096601431	-0.0071248822603902	0.1088831699377573	0.2549257666562065	0.1057153591948560	
+3.9859999999999998	0.0398525795992279	9.8241501537419484	0.0262345662379258	0.1623251086097087	-0.2724654893189491	-0.0249922973633646	
+3.9869999999999997	0.0572351033232563	9.8194765633090491	0.0149448655981774	0.1480269773439179	0.1164544381106818	0.2121990638330388	
+3.9880000000000000	0.0681067902041638	9.8097499182391790	0.0231994153907687	0.1722412609563617	0.1267098760414188	0.2288040190137174	
+3.9889999999999999	0.0441441463668015	9.8307256146400963	0.0222356938959492	0.0305896013442805	-0.0442517482158042	0.2447619214856194	
+3.9899999999999998	0.0577380987070005	9.8489243724116342	0.0153483844563384	0.0622216405187439	0.0792430035426394	0.2371003935624306	
+3.9909999999999997	0.0669233935526302	9.8319089645423183	0.0046549474085344	0.0127704659648402	0.1083454353544533	0.1517100128063375	
+3.9920000000000000	0.0651454466167995	9.8244387027230751	0.0338329401018345	0.0833968821984620	0.0987620130016258	0.3508302101519816	
+3.9929999999999999	0.0262759119149296	9.8371655648249074	0.0081302141558680	0.1126639176217328	-0.1318623048475284	0.0752433461050224	
+3.9939999999999998	0.0727462684299639	9.8130202330880874	0.0092567073509469	0.2681111164050952	0.0848945286563789	0.2342433103290794	
+3.9949999999999997	0.0704535262918096	9.8255042359140869	0.0155861831915131	0.0200715824337912	-0.1509939910839231	-0.1074196107468492	
+3.9960000000000000	0.0543491654863993	9.8148741564573410	0.0104648497215495	-0.1557982118490464	0.2821993844581860	-0.0321052482817181	
+3.9969999999999999	0.0540880989939406	9.8262729360716570	0.0284994245598463	0.0983609740469402	0.0082160601746288	0.3099912460184436	
+3.9979999999999998	0.0491728162817777	9.8304139852645491	0.0248787040673622	0.0409349563517376	0.3045431821437377	0.1664789708111091	
+3.9989999999999997	0.0453375568009324	9.8011126797251649	0.0186405443848145	0.3447006513284012	0.0385756982296002	0.0815190666482168	
+4.0000000000000000	0.0460869545992723	9.8275785902873931	0.0067860824323701	-0.0598432838539837	0.0765243952293566	0.1276476248461726	
+4.0009999999999994	0.0598602083088027	9.8152810780564241	0.0285065446621382	0.2852328231244344	0.0411364456189559	0.1223947283686752	
+4.0019999999999998	0.0522449102508977	9.8273800231225295	0.0130684574731067	-0.2478102933560679	0.1487147409966283	-0.0518097533124011	
+4.0030000000000001	0.0516611839101091	9.8274588020202049	0.0295755349840879	-0.0180396101337940	-0.0655448882006623	0.2210918891084116	
+4.0039999999999996	0.0699966780150098	9.8220311207558133	0.0111197264652649	-2.8315556932343706	-0.1285497377766789	0.1967018395809401	
+4.0049999999999999	0.0749613715051371	9.8211090432002468	0.0619651242903609	-2.8196972599057957	0.1998396197527786	-0.0041472968555368	
+4.0060000000000002	0.0529864014998665	9.8140088850139424	0.0701809785619275	-2.9989215689772237	-0.2057124040550368	0.2177923999877482	
+4.0069999999999997	0.0576597767011104	9.8483860017941236	0.1131328155739236	-3.1163314514511531	0.1271154707167664	0.1483339035138783	
+4.0080000000000000	0.0452546047768356	9.8065055750483126	0.1631686127911920	-3.0487364946271622	-0.1812838145607109	-0.2400095350381645	
+4.0090000000000003	0.0527319112675846	9.8154681488884510	0.1579904183462845	-3.1047776450497193	-0.0885308922228260	-0.0037957594773692	
+4.0099999999999998	0.0360842258465576	9.8229147251091451	0.1733804043062129	-3.1899954831849566	-0.2423192142437511	0.0021748432448949	
+4.0110000000000001	0.0572397851682356	9.8099144184240092	0.2395212512617608	-3.1394084161768685	0.0281635165019883	-0.0685461089647047	
+4.0119999999999996	0.0449340616712198	9.8226256511677281	0.2847746344677652	-3.2300109344753829	-0.2989056624105350	-0.0565019337582831	
+4.0129999999999999	0.0623365798182402	9.8229042234225865	0.2924373145591094	-3.2587149853126522	0.0530357074876693	-0.0265069143546292	
+4.0139999999999993	0.0457922414736832	9.8056475601032762	0.3408074338015775	-3.2076632676181469	-0.0251636690959443	0.0745237571318129	
+4.0149999999999997	0.0668436088489743	9.8018458278325262	0.3553850186239471	-2.9503417351745416	0.0515010391747603	0.0614059479648606	
+4.0160000000000000	0.0612731299158423	9.8090937637481375	0.3772934027088053	-2.9747363186901099	-0.0060894337804213	0.2781838276404465	
+4.0169999999999995	0.0655527634587755	9.8184791780479035	0.4217459110119006	-3.5663355340330769	0.0629450315341212	0.1745754821387916	
+4.0179999999999998	0.0602193832429134	9.7985341268223820	0.4487868222031138	-3.0430581142968816	0.1587084324989700	0.0391917470613606	
+4.0190000000000001	0.0520643611269847	9.8382912074172300	0.4910015501676614	-2.9443337082303782	0.1214825254957030	0.4222524288796874	
+4.0199999999999996	0.0728092763199134	9.7938398362868604	0.5268593890231039	-3.3614117028086934	-0.0250541398298077	0.0533031901038614	
+4.0209999999999999	0.0538082525743254	9.7893858989325437	0.5317390377819098	-3.1452730089801468	-0.1813217733167697	0.2384663756862559	
+4.0220000000000002	0.0390726138862974	9.8107297100568847	0.5807566176838341	-2.8677708453945558	-0.0330044027465115	0.0735696387160885	
+4.0229999999999997	0.0489188941389287	9.8062029520445737	0.6022413534307424	-2.9922096232375965	-0.0529701198210227	-0.0217747538434782	
+4.0240000000000000	0.0512078911890664	9.8057631211052119	0.6423239020856226	-3.0905084602007049	-0.1580990694171636	0.0276034425391916	
+4.0250000000000004	0.0546395822407481	9.7810581004971482	0.6597261673873529	-3.1696037547679472	-0.3265772283633201	0.0399598450723173	
+4.0259999999999998	0.0460102175851206	9.7839557098787040	0.6933221132657956	-3.1401535543693275	-0.0595782957544613	0.3026439893936633	
+4.0270000000000001	0.0345270231076644	9.7898636095351641	0.7264730435583487	-3.3179508416278214	-0.0024317151785418	0.0119136051734927	
+4.0279999999999996	0.0677263549829876	9.7918017694290693	0.7555107509834232	-3.1900060828335826	0.1706486481664676	0.2279462057683228	
+4.0289999999999999	0.0585555067647748	9.8021145214745928	0.7622470732187726	-3.1497384649261284	0.0266570480190613	0.0265613420870392	
+4.0299999999999994	0.0705206596965775	9.7688269774846912	0.8131696258618275	-3.1039706323446703	-0.0582439567410203	0.1050957279880921	
+4.0309999999999997	0.0506651422798451	9.7932449663120078	0.8420687220377128	-3.4746933459788165	0.1406599021560661	-0.0142646362081737	
+4.0320000000000000	0.0544815181146618	9.7755921708026126	0.8949389234882921	-3.1450618592090058	0.0243423143166080	0.4243073058141623	
+4.0329999999999995	0.0472983092860315	9.7583918067260456	0.9080081085518501	-2.9089635688435664	0.1041301937942326	0.2855857524136912	
+4.0339999999999998	0.0474565998213603	9.7769243647782336	0.9283210472592446	-2.8586135559369175	0.0833107563208563	0.0651588570654067	
+4.0350000000000001	0.0592364339938493	9.7779151283379804	0.9597379508597168	-3.1005644586539596	-0.0985407295999449	-0.0458444993753502	
+4.0359999999999996	0.0371317294193231	9.7936011641094787	1.0159320886961898	-3.2054906696230749	-0.1129938317249956	0.0954504889216774	
+4.0369999999999999	0.0332723483388938	9.7731949628864658	1.0373825855876970	-3.0424740092004181	-0.1609635129541307	0.1374543822496385	
+4.0380000000000003	0.0684250892752452	9.7385905883651294	1.0639109412855028	-3.1332646649786313	-0.2443283768643206	0.1543354682946695	
+4.0389999999999997	0.0714703250155264	9.7477499095702402	1.0886187403622996	-2.9695858912509765	-0.0235840201265302	0.1017865846389223	
+4.0400000000000000	0.0581700937683856	9.7394197753599023	1.1144247246636791	-2.9490168117739692	-0.0706535634603213	-0.0160942891763141	
+4.0410000000000004	0.0419936605781230	9.7572458757368032	1.1634460073156720	-3.1985160659391858	-0.0207525513865261	0.3230376414140114	
+4.0419999999999998	0.0499758600248360	9.7338574138572529	1.1824593664256369	-3.1223069528821146	0.1511083164969673	-0.0183112830514038	
+4.0430000000000001	0.0637993614622836	9.7327682639906783	1.2025648864224097	-3.2847578895892720	0.1678701250524731	0.0241818701005239	
+4.0439999999999996	0.0583054104147637	9.7620335135433525	1.2488923335965063	-3.0634409483623424	-0.1344510320023469	0.0138344172426352	
+4.0449999999999999	0.0698332353080740	9.7131718144772208	1.2785615892838553	-3.0640531676733462	-0.1711547371841721	0.2202898696556228	
+4.0459999999999994	0.0463813842548767	9.7446908689788305	1.3211836629025542	-3.0947583997336183	0.1166140540765749	0.2660258082541139	
+4.0469999999999997	0.0609405774279621	9.7414410666954758	1.3283692453251701	-3.2222770361467741	-0.3484990033674413	0.1566233808287820	
+4.0480000000000000	0.0600322771411577	9.7218060030039553	1.3733738570658620	-3.1884231324595813	-0.1530825222649700	0.2115769323129275	
+4.0489999999999995	0.0397998453447243	9.7374521941716772	1.4033104366055440	-3.3214733770740295	-0.1106032688468028	0.0674257806434423	
+4.0499999999999998	0.0610675451963809	9.7135670972839527	1.4299292877761722	-3.0496308163276185	-0.0126329290499268	0.3754670362024475	
+4.0510000000000002	0.0435087274548292	9.7092301432635608	1.4608320644110762	-3.2962383029450182	-0.1991217859716469	0.1298500703482266	
+4.0519999999999996	0.0643498242281123	9.7170108849333658	1.5017687757668907	-3.3061658105674891	-0.0115402018555714	0.1072364272607073	
+4.0529999999999999	0.0724298553189732	9.6942217114873444	1.5150203468226873	-2.9139000213470205	-0.1319107645923900	0.2907524475865119	
+4.0540000000000003	0.0581148215428752	9.6958769004396448	1.5377889602347043	-3.0130271011633445	0.0435019989577824	-0.1098283720133214	
+4.0549999999999997	0.0449081141026994	9.6821400800864534	1.5855170573530362	-3.4058835570927228	-0.1932723994641968	0.1628373733687631	
+4.0560000000000000	0.0683097603191827	9.7003389914635818	1.6104039671687171	-3.0043429237085935	0.0931601991205290	0.1142995154389637	
+4.0570000000000004	0.0710546873744023	9.6822477480821441	1.6352694421110643	-2.9537681394890054	0.2777473022193196	-0.1096181953810663	
+4.0579999999999998	0.0342828371596922	9.6749133343770666	1.6745735792324978	-2.8657519849358835	0.0457370188363697	0.1798920980676131	
+4.0590000000000002	0.0596455594749338	9.6595926542241326	1.7037159256295489	-2.9830031621022366	0.1628207900827627	-0.0216134035179216	
+4.0599999999999996	0.0350562288234417	9.6685314169197234	1.7374821122516813	-3.2505217135522040	0.1518653946604837	0.0106517030532658	
+4.0609999999999999	0.0524062285966886	9.6561120131465312	1.7591542704004715	-3.1519781107902043	-0.1458024029518080	-0.2804887389571087	
+4.0619999999999994	0.0573240850744961	9.6763790076715459	1.7857319818691726	-3.1742292685974074	-0.1099917768887638	0.1383039884531664	
+4.0629999999999997	0.0384354452573281	9.6593887969265388	1.8500915896284063	-3.1224641716791570	-0.2575131485756216	0.2113930487370009	
+4.0640000000000001	0.0522305870951125	9.6567628122703226	1.8608538565459758	-2.8628702659692169	0.0028161121545508	0.0074278449930708	
+4.0649999999999995	0.0637899854129608	9.6318068850649734	1.8831910407758861	-3.2203459022970562	0.0760447198426575	-0.1174876297807815	
+4.0659999999999998	0.0389674115538514	9.6275993820386088	1.9130780986094227	-3.2170163037489727	-0.1237273315841051	0.2160136045264367	
+4.0670000000000002	0.0492426947461571	9.6298594976695853	1.9469728133095277	-3.2527481432795384	-0.0345133228173322	0.1687147419681838	
+4.0679999999999996	0.0474371869675275	9.6203162208508353	1.9595377488934396	-3.2639721642580364	-0.0744935462218133	0.1598984027805090	
+4.0690000000000000	0.0550854405170492	9.6244306052313089	1.9981463841635343	-2.8251581265145398	-0.1113540660125605	0.0345008562816110	
+4.0700000000000003	0.0472276063122024	9.6174430210490041	2.0313587926172647	-3.0953501366818776	-0.0220751483928285	-0.0771278867838728	
+4.0709999999999997	0.0643289895521500	9.5888267188186642	2.0715028118495664	-3.2565861859351690	0.1060998705563791	0.1129518858283732	
+4.0720000000000001	0.0562558706579061	9.5874707732785076	2.0981539081672498	-2.9695342346022362	0.1132947539019265	0.4103661668270916	
+4.0730000000000004	0.0482075465323133	9.5804257436739118	2.1358181037182833	-3.2471553868482212	-0.1992153181742252	0.2469350932626530	
+4.0739999999999998	0.0686429688064733	9.5827525823998272	2.1436400852724651	-2.8363661642153923	-0.1398300237936368	0.1810813657503942	
+4.0750000000000002	0.0565765851485681	9.5932969324406763	2.1866869763140198	-3.2655848430514545	-0.0086698001337886	-0.0117291485068871	
+4.0759999999999996	0.0510361713638679	9.5651540551703285	2.2058476954047821	-3.4008773312696898	0.0116317270150797	-0.1102146147850700	
+4.0770000000000000	0.0559553169941042	9.5649208956442298	2.2242011181096757	-3.4553427038955689	0.1198487516374710	0.0597949676145802	
+4.0779999999999994	0.0619821297873286	9.5411016786989844	2.2698506383027830	-3.2487974502610726	0.0779293574733543	0.0071004859995475	
+4.0789999999999997	0.0499138015482130	9.5635725313443185	2.3034416631400920	-3.1560105093186692	0.1259119472781187	0.1529166836201722	
+4.0800000000000001	0.0476724449210601	9.5344686256608213	2.3473603601955007	-3.1264048443233197	0.0774562557740615	0.0471992150324145	
+4.0809999999999995	0.0578978362246420	9.5293225765071679	2.3657224495800833	-2.8926454109846516	-0.0196873185194331	-0.0355230518357404	
+4.0819999999999999	0.0502455247899917	9.5275694529537027	2.3838531989735285	-3.0479122121926059	-0.1421287808643719	0.1071744707555127	
+4.0830000000000002	0.0457265839546356	9.5019257542939837	2.4200430399388857	-2.9982264173929374	-0.4165335139971110	0.1032755930403713	
+4.0839999999999996	0.0576389036003959	9.5006610514164347	2.4663905876413668	-3.1801129086529949	-0.0502999448526505	0.0508582731366122	
+4.0850000000000000	0.0713951466521830	9.5104158522580686	2.4682095394437176	-3.1820231835924275	0.2237209722334190	0.0610271798793153	
+4.0860000000000003	0.0342983351706299	9.4957757101995011	2.5144978893232186	-2.8024111809736993	-0.2446250652233071	0.0849976935726257	
+4.0869999999999997	0.0476451826919102	9.4940708704809698	2.5401414162401141	-3.3084195755372834	0.0161325564691641	-0.2153376205112246	
+4.0880000000000001	0.0565333667721234	9.4578867486224301	2.5791060797240482	-2.8451974599964158	0.0159153748893231	-0.1128465203299126	
+4.0889999999999995	0.0708445561473139	9.4670485943971094	2.5976448574380955	-3.1040977220689072	-0.0170015062599637	-0.0636422936883339	
+4.0899999999999999	0.0464767982015780	9.4546976172108508	2.6113076739005883	-2.9885926212340954	-0.0029896667187160	-0.0640768069137386	
+4.0909999999999993	0.0500821806361226	9.4577275588793679	2.6632555204081889	-3.2302327257969683	-0.1248782141149907	0.0562597674419852	
+4.0919999999999996	0.0342426188158065	9.4180923265254251	2.7065754096926513	-3.0123215368517915	-0.1229436796607381	0.0542508041834366	
+4.0930000000000000	0.0755813029441014	9.4296629066156896	2.7261196055296621	-3.2128786614572227	-0.1041021827219782	-0.1915895427576417	
+4.0939999999999994	0.0523842009738347	9.4191763810113898	2.7416598972146642	-3.1314865800741511	-0.2389404966794581	0.0032177350601641	
+4.0949999999999998	0.0725953901862229	9.4156607141848880	2.7872765344718635	-3.2253687379501477	-0.0357567698939117	-0.0268314775092369	
+4.0960000000000001	0.0570288146678497	9.4087040371958235	2.7965749650551124	-2.9978151050600368	0.0562685368752054	0.0520869244945364	
+4.0969999999999995	0.0521037512716363	9.4074916443555132	2.8369119577490056	-3.2132372958735953	-0.0751692303641136	-0.1093908269207284	
+4.0979999999999999	0.0455909391711864	9.4009287843106168	2.8623689081346617	-2.9781594486193592	0.0512227004743560	0.0022884936776760	
+4.0990000000000002	0.0589137165312611	9.3837594792464767	2.9159174378911286	-3.2240524776780624	0.1280886451396533	0.0541531496712882	
+4.0999999999999996	0.0720390354343390	9.3771303001684831	2.9535740094180789	-3.0902506771400504	-0.0314022638042640	0.2625828777258889	
+4.1010000000000000	0.0526179819827210	9.3660696884902546	2.9620811128923976	-3.0206382705449024	-0.1395912702296415	0.0430577314235318	
+4.1020000000000003	0.0701634009258926	9.3458118976017364	3.0043831463733310	-3.2556033317051249	-0.0679744961825348	0.1215622342579655	
+4.1029999999999998	0.0758858104325383	9.3355251945789526	3.0376511096050871	-3.0090344726513680	-0.1553351083300991	-0.0070429500097772	
+4.1040000000000001	0.0464152963765973	9.3400173237690307	3.0337964627420111	-3.0906326600100220	-0.2212326022304388	-0.1217283365934112	
+4.1049999999999995	0.0513470712749248	9.3278033494816412	3.0536095437020827	-3.2765718882839940	0.1978828712789158	-0.0816827611251600	
+4.1059999999999999	0.0539371338197815	9.3063620372193778	3.1116138976657388	-2.8871855781675144	-0.0157100378646137	0.1216480468011775	
+4.1069999999999993	0.0631581809692814	9.3065336217178665	3.1462254026948822	-3.1338314426269021	0.0496465612989471	0.1143040224686915	
+4.1079999999999997	0.0670308791964020	9.3002261966049975	3.1681370750547657	-3.2569057070864624	-0.2694575381110575	0.2974176051687053	
+4.1090000000000000	0.0695220600878574	9.2826247729137954	3.2124593171919806	-3.0581352032225300	-0.2288784900124051	0.1948774564458916	
+4.1099999999999994	0.0357961747837188	9.2781983488142252	3.2243911786115937	-3.0631375476294718	-0.1022566752892819	0.1108832577650229	
+4.1109999999999998	0.0387581740924749	9.2600640095121296	3.2289965936142422	-3.0659323870025004	-0.2534033401825286	-0.0633470838179378	
+4.1120000000000001	0.0513474166739658	9.2784137790837331	3.2881018957443549	-2.9912046295760590	-0.1375999906241031	-0.0457216465887035	
+4.1129999999999995	0.0552815971888656	9.2475866276679977	3.3168000305534027	-3.2866862338306726	0.1178969924578705	-0.1825003895200917	
+4.1139999999999999	0.0458295873721319	9.2284902667915016	3.3270186550686489	-3.0384159285769541	-0.0033493780752481	0.3938702305532069	
+4.1150000000000002	0.0559760232703913	9.2359516560757076	3.3609594367164339	-2.9524712895981402	0.2683694487698244	-0.0385759438286929	
+4.1159999999999997	0.0494358521329429	9.2077209715292696	3.3880596567172176	-3.2681021475264851	0.0396904696055843	-0.0982340253916914	
+4.1170000000000000	0.0374115880770862	9.2021913963836379	3.4281999928863667	-2.8901216407025170	0.1381600882921015	0.0382063781636612	
+4.1180000000000003	0.0566092226033360	9.1826344727298554	3.4426141768507068	-3.2935735723455126	0.0166384720952819	0.1139265617760511	
+4.1189999999999998	0.0537190990636396	9.1725499249051836	3.4869312572306934	-3.0870799609210549	-0.0476972717925348	0.4507956365993823	
+4.1200000000000001	0.0619427106913488	9.1712155036223830	3.5179691076235566	-2.8694089350565113	-0.1747705923489388	-0.0931578764344111	
+4.1209999999999996	0.0493559414888088	9.1664843507086484	3.5313152257036098	-2.8007499098417945	-0.2303251720481733	0.0589953012433515	
+4.1219999999999999	0.0883302055065970	9.1353874184217396	3.5703597304725236	-3.2704333263749796	0.0042695242226442	0.1779900409781249	
+4.1229999999999993	0.0708198881398228	9.1286479541638510	3.5874748883642065	-3.0892770366551150	0.0870914199432618	0.0690650622854904	
+4.1239999999999997	0.0529207154779826	9.1290299954108800	3.6204319822688404	-2.9980090007662441	-0.0070162439604831	-0.0317356702273811	
+4.1250000000000000	0.0431254400441283	9.1064241614626322	3.6613696678830943	-2.9823569917772899	0.1191652006966939	0.1882243149344055	
+4.1259999999999994	0.0650253093906584	9.0855204713693620	3.6812026000218565	-3.2818391935283269	-0.3362966785375098	0.3172700183904555	
+4.1269999999999998	0.0494803737602562	9.0955510849709889	3.6933547711014443	-3.2573795238066472	-0.0874891622999124	0.2606115728669302	
+4.1280000000000001	0.0607881710571337	9.0629068511448256	3.7390642378805170	-3.0202576453811205	0.0487183176913536	0.3245376258214787	
+4.1289999999999996	0.0333160354407072	9.0725711213476767	3.7500727513075915	-2.9807410659832088	-0.0394235523822744	0.1113283095823488	
+4.1299999999999999	0.0294038302522919	9.0638738162311672	3.7928246844611526	-2.9970899868181062	0.0201089064199064	-0.0316288874511088	
+4.1310000000000002	0.0404521877095556	9.0630801235994944	3.8209809954761211	-2.9530758468486704	-0.0192894869637926	0.0785115209104278	
+4.1319999999999997	0.0565685836020201	9.0422176474024152	3.8534732008252992	-3.1879914028185241	-0.0432085240553400	-0.0976728292685461	
+4.1330000000000000	0.0578988054491194	9.0260415568823937	3.8579027425881627	-3.1738308968389153	-0.0321700664297299	0.1596664486762425	
+4.1340000000000003	0.0602537115127839	8.9990086547355830	3.8910714232600907	-3.0106372748248020	-0.2328437692427207	0.1091292850646617	
+4.1349999999999998	0.0489157052936504	8.9975761087792829	3.9268033932970305	-2.8445908189000213	0.1264583353274180	0.0157515930494029	
+4.1360000000000001	0.0752742728300265	8.9920159746401307	3.9669408529514727	-3.1127962382951679	-0.0134841469950212	0.0298634158584663	
+4.1369999999999996	0.0596260011317000	8.9664791270510236	3.9950613277158418	-2.8660451863507026	0.2367417007827670	-0.1883500727153767	
+4.1379999999999999	0.0760741138820129	8.9768354969509154	4.0136319822487048	-3.0600351801225267	-0.2498773027148728	0.2476709467540238	
+4.1389999999999993	0.0541840819850061	8.9406831341212438	4.0530026690607448	-3.1650495087928565	-0.0203519956389621	0.0178860268130585	
+4.1399999999999997	0.0411860700147448	8.9202434049120836	4.0519144196838521	-2.8872961050856842	0.0068479112409919	-0.1515372134838898	
+4.1410000000000000	0.0692183008742472	8.9087939799355063	4.1076881518160828	-3.2310186107731562	0.0829302892211628	0.0173898123733471	
+4.1419999999999995	0.0382775170716649	8.9079058499681771	4.1445306944951659	-3.2582813252188108	-0.0665161605198814	-0.0260153181258526	
+4.1429999999999998	0.0527930675334404	8.8797405438616455	4.1562146727949711	-3.1879489481176240	-0.0121143715539912	0.1255609225511058	
+4.1440000000000001	0.0442138289050659	8.8837679048274314	4.2004590045121404	-2.9818402048642878	-0.1612346348727110	-0.0133847087361706	
+4.1449999999999996	0.0825586845533731	8.8536921691077293	4.2165767265158411	-2.8765719647807195	0.0265158699832093	0.0918757782850205	
+4.1459999999999999	0.0573869796407830	8.8476528567115462	4.2608406959592031	-3.1288773047684195	-0.0379483395608088	-0.0025175490799147	
+4.1470000000000002	0.0672434447252937	8.8353534177554973	4.2580937694657894	-3.1418596116367330	-0.1057775288215215	0.1593041414118431	
+4.1479999999999997	0.0460383388847873	8.8289409569960853	4.2980794009185619	-3.1334922760764465	0.2103083303051781	0.3508672879026522	
+4.1490000000000000	0.0429289553896051	8.7836223716397708	4.3235074676751077	-3.3305297838897574	0.0085828210258935	0.0622428194728440	
+4.1500000000000004	0.0553468859522282	8.7879807557632095	4.3417324409462790	-3.3814942900370268	-0.1006036650110733	-0.1317817513272947	
+4.1509999999999998	0.0442058153205993	8.7773709963326016	4.3778564975749834	-2.8585834778816905	0.0405739682522246	0.1689338054023854	
+4.1520000000000001	0.0392693725357788	8.7606646504778762	4.3967246760454373	-3.0199109859887212	0.1015833699701819	-0.0166765096606790	
+4.1529999999999996	0.0601422447752824	8.7642906903582958	4.4321142772557245	-3.1745092099966010	0.0327332901345881	-0.0251021605623289	
+4.1539999999999999	0.0488615197299334	8.7400539914470663	4.4790501854387106	-3.0458113880522339	0.1582655451131001	-0.0140984141995628	
+4.1549999999999994	0.0419080804000454	8.7124212992790326	4.4882222458020324	-3.4110027657770559	0.2937419046346109	-0.0435835046706333	
+4.1559999999999997	0.0688389191473405	8.7126552248060545	4.5345483051601123	-3.0875842414204731	-0.1463948030491121	0.2134589697510904	
+4.1570000000000000	0.0765257277219256	8.6981122512218700	4.5429051778958076	-3.2162067316223846	0.0177533697526236	0.1057772458933376	
+4.1579999999999995	0.0672390573076116	8.6779188273950414	4.5744269105507271	-3.0659901188830720	0.0048334850853988	-0.0338156295899096	
+4.1589999999999998	0.0689330796489376	8.6602909412478173	4.5953175526861383	-2.9769590609523853	0.1936406208438012	-0.0168414858523943	
+4.1600000000000001	0.0668995164608434	8.6473081234707472	4.6354643559229869	-3.0904921588003078	-0.1163596886032470	-0.0654820449801441	
+4.1609999999999996	0.0479301834822840	8.6492576528669307	4.6575719927759609	-2.9751603724830336	-0.0819567773818722	-0.1230581471999962	
+4.1619999999999999	0.0533161667420740	8.6358745853789518	4.6924654025483488	-3.1572287206075318	-0.3116122508535913	0.0543208155659786	
+4.1630000000000003	0.0540778935426067	8.6246710146065126	4.7353930623998481	-3.0591602555829107	0.1792821304610126	0.2877941103034411	
+4.1639999999999997	0.0590458914928895	8.5822264203916916	4.7595648226355110	-2.9183730882334840	-0.2463827665051938	-0.1520707712367048	
+4.1650000000000000	0.0575448453660941	8.5651724635234636	4.7385765940351101	-3.2209038023818004	0.1347766391614039	0.3251067907597262	
+4.1660000000000004	0.0639910352357374	8.5560098944697440	4.7927417518749778	-2.8721033887767886	-0.1485205636534898	0.0647642312609372	
+4.1669999999999998	0.0644930582659092	8.5357883022428993	4.8137087290095142	-2.9561386050652678	0.0353379997596302	-0.0281500824790706	
+4.1680000000000001	0.0665244427676558	8.5418068793401485	4.8666320576693041	-3.0913085696710150	-0.0055704459376650	0.2115448118602893	
+4.1689999999999996	0.0311395552999002	8.5335674225042943	4.8727224188961413	-3.1157672259194031	0.0123654551592487	-0.2024883477830656	
+4.1699999999999999	0.0464665409882320	8.4929477839732535	4.8978393647528717	-3.0537543603297355	0.0302349633497140	0.1711006612501727	
+4.1709999999999994	0.0510058586186490	8.4997095472023165	4.9197132951721434	-3.1425048673800995	-0.1144919589098289	-0.1576891917138283	
+4.1719999999999997	0.0547778551621130	8.4849539951081798	4.9439720317652105	-3.0827772627432948	-0.0069167132994719	0.0059559478200847	
+4.1730000000000000	0.0651236455558642	8.4574366182358052	4.9698500940800674	-3.1036258746705139	-0.1613240099444884	0.5092471501283874	
+4.1739999999999995	0.0482340008601684	8.4424540923003768	5.0069131627032393	-3.0171821205006339	0.0428207912455871	0.3417073562704577	
+4.1749999999999998	0.0371096057327185	8.4106736603243561	5.0308214433111944	-2.9006078639293267	0.0939163490366059	0.3163739758421226	
+4.1760000000000002	0.0501171528081238	8.4217160501666939	5.0495672902358706	-2.9185747936957056	0.0472668136211786	0.0833797395603111	
+4.1769999999999996	0.0512401142814886	8.4046519558907455	5.0774850230500643	-3.1765580103134230	0.0502260898345795	0.0376783744362440	
+4.1779999999999999	0.0596195061104885	8.3752365309567054	5.1253284498931926	-2.9980623880538277	0.0253796855448766	0.1139461275571648	
+4.1790000000000003	0.0509736201669094	8.3654759637991827	5.1432409675213995	-3.1003845659866007	0.1447322838260522	0.3293831842899965	
+4.1799999999999997	0.0455598706020991	8.3730722273547116	5.1637707846642691	-3.0915858652174317	0.1370344896085214	0.1673462729795706	
+4.1810000000000000	0.0824214009262636	8.3149610818893773	5.1744234040990698	-2.9982033357820388	-0.0927781298644182	-0.1027635016019374	
+4.1820000000000004	0.0424003869812734	8.3071526755846854	5.2256814574490686	-3.1872146438123994	0.0782955977620293	0.2276959910931221	
+4.1829999999999998	0.0496638439655376	8.2879113107446294	5.2371389690154144	-3.4135453392044779	0.0763500644538659	0.0764542752778869	
+4.1840000000000002	0.0663478443050274	8.2834111412919125	5.2786203390350002	-3.0410597709030758	-0.1047050301480928	0.1088518021388482	
+4.1849999999999996	0.0486869143095161	8.2641608411713285	5.2925063449476717	-3.4877427469049875	-0.0166867589475206	0.0587179004140210	
+4.1859999999999999	0.0426775032758419	8.2431121802015443	5.3193886837197208	-3.2452407033802211	0.1947783496071500	0.0726773801576943	
+4.1869999999999994	0.0488553268594589	8.2372048055931160	5.3480761792415654	-3.0866211946311211	-0.0456244826274074	0.0433241556885584	
+4.1879999999999997	0.0438283596101952	8.2239581653663496	5.3523671022662240	-2.9700484546756400	0.0019354417499181	-0.0854567465161917	
+4.1890000000000001	0.0588938117529855	8.2090557918496696	5.3797393870224877	-3.1698407516919191	-0.0811646536062038	0.0479383027097510	
+4.1899999999999995	0.0591692646409277	8.1731191062797048	5.4122760598330499	-2.7815272478239730	-0.0901208916978124	0.0882041235595163	
+4.1909999999999998	0.0615894389970987	8.1446308018709139	5.4434517756307432	-3.2347917147163807	0.0245996528835397	0.2796100278986693	
+4.1920000000000002	0.0644825020978651	8.1247024081951196	5.4619714151309333	-3.1670811049639576	-0.1230763382943142	0.1699923151791160	
+4.1929999999999996	0.0514875513646159	8.1111284149652310	5.4978500165048354	-3.0438223258612225	0.0140241289058707	-0.1184666652768793	
+4.1940000000000000	0.0729993325636789	8.1000589199474469	5.5490160309121874	-3.1774396848322142	-0.0528227897652763	0.2827685294315646	
+4.1950000000000003	0.0508363538033441	8.0811797801386298	5.5413607204848514	-3.1454419346006119	0.1294473632779603	0.2356118148985891	
+4.1959999999999997	0.0547112533548387	8.0679147465047745	5.5785458109830346	-2.9233877128893933	0.0738259920018544	0.2103278668517594	
+4.1970000000000001	0.0528144848386650	8.0906278594713434	5.6140006237676152	-2.8739956581178281	-0.2537553946205378	-0.0792917144754143	
+4.1980000000000004	0.0507581029674585	8.0319940306698232	5.6198260740020531	-2.9049941949981575	-0.1460709504901544	-0.3305399614397255	
+4.1989999999999998	0.0661660739983787	8.0317682252407643	5.6535207145741984	-2.9883327950665866	-0.1327865630448581	-0.1186075278297807	
+4.2000000000000002	0.0418511687809604	8.0213077911350670	5.6605189120505672	-3.0027278946743885	-0.1115359324939333	0.0288273817793045	
+4.2009999999999996	0.0515467075377853	8.0010803849223855	5.6759248621367204	-3.1084754061590210	-0.1775410383761110	0.1972982953181238	
+4.2020000000000000	0.0436602893581692	7.9751803162617083	5.7334858846732661	-3.1627517614440017	0.0643776778346357	0.0948217303687920	
+4.2029999999999994	0.0790946591289259	7.9593175989429579	5.7527631104212489	-2.9714500208766368	0.0540075558490155	0.1264991527356454	
+4.2039999999999997	0.0827836267353913	7.9534117787506915	5.7838221311704041	-2.8064340567018107	-0.0216049143319754	-0.0678673010322900	
+4.2050000000000001	0.0584155984677345	7.9270029288042796	5.7957486048380353	-3.1574734858378375	-0.0994592110628382	0.2235000210602180	
+4.2059999999999995	0.0698648556757487	7.9101456726914305	5.8257843084418157	-3.3380914406048872	0.1302641953365709	-0.0476623309862680	
+4.2069999999999999	0.0593875531102031	7.8791304550891983	5.8363730468425272	-3.0947821223222181	-0.0127765405280812	0.1006610005981437	
+4.2080000000000002	0.0723593071645333	7.8581802505593696	5.8537801390715503	-3.2919305322403396	-0.0732847848924545	-0.0422823851912518	
+4.2089999999999996	0.0476222119148881	7.8487380735450420	5.9148626937631423	-3.2402685613687163	-0.1466220896638830	-0.0115713289458849	
+4.2100000000000000	0.0522452257842173	7.8203900118914413	5.9358529834095251	-2.9894700632261642	-0.0320459439013926	-0.0447662274987412	
+4.2110000000000003	0.0543862258901803	7.8334889280819251	5.9407315449353622	-3.2768292353288904	-0.0560257296258825	-0.1067249686618263	
+4.2119999999999997	0.0461584012172729	7.7979371537501869	5.9721337822635983	-2.8699545240414750	-0.1286670272978470	0.2442615665171065	
+4.2130000000000001	0.0385680459767836	7.7667629039264083	5.9750911547552148	-2.9454429639383961	0.1346585441334663	0.0096302145825788	
+4.2139999999999995	0.0698033909136140	7.7422891224132693	5.9990855629844457	-3.1763028510736762	-0.0455530890803556	-0.1350178444742660	
+4.2149999999999999	0.0422970267041671	7.7285631478113475	6.0637153888858615	-3.2916114838933108	0.0859002898164075	-0.1194908906052457	
+4.2159999999999993	0.0477865127689045	7.7134090289488979	6.0909913510575979	-3.0884094627768715	0.1024749092003291	0.1605177258452384	
+4.2169999999999996	0.0487305159239775	7.7031414826122866	6.0760303275709902	-3.1992331177426481	-0.2257792102434236	0.0733621073518530	
+4.2180000000000000	0.0607496731241322	7.6480973874334035	6.1221624979652809	-2.8244140827203861	-0.3840276916887553	0.2111588650807182	
+4.2189999999999994	0.0535507799699627	7.6441380230562377	6.1241401476797179	-3.2071618813344016	-0.1849715418752637	0.0589876448325001	
+4.2199999999999998	0.0431573297322031	7.6249172406936934	6.1494744129454233	-2.9904769827015438	-0.1672545973497596	0.0592067184647453	
+4.2210000000000001	0.0653753242249661	7.6313690499740101	6.1859440496513880	-3.2690129787656095	-0.0846526463842770	-0.0397973067137634	
+4.2219999999999995	0.0474732430308695	7.5909575871640884	6.2091482130216296	-3.1175468397849699	-0.0644279223324203	0.2127920677239670	
+4.2229999999999999	0.0586277579867158	7.5748773274867212	6.2278572782179253	-3.0025584850066158	-0.0351860705610602	0.1463019749190086	
+4.2240000000000002	0.0715877235563590	7.5739653650796335	6.2599266286630497	-3.3773689323460641	0.0830650967606990	0.2299991176304966	
+4.2249999999999996	0.0244486552266929	7.5454961420255806	6.2836446221901934	-2.8937908295206851	-0.0510484684569960	0.1226575293917931	
+4.2260000000000000	0.0592400389468961	7.5056102783846823	6.3190597710584013	-2.9481761773245210	-0.2088883855536973	0.2552825079024280	
+4.2270000000000003	0.0524810482191574	7.4866390614288907	6.3133729631673736	-2.8037196803809783	0.2571685897062580	-0.0009133719560008	
+4.2279999999999998	0.0544568615076626	7.4738327959635686	6.3437903392671000	-3.0239135035806957	-0.0496894853517499	0.0973893687420815	
+4.2290000000000001	0.0530151688915045	7.4508399682028772	6.3897832373199899	-3.0236503615732038	-0.0694093669153849	-0.2710596437418923	
+4.2299999999999995	0.0725644147762278	7.4372004126974538	6.3952221705812402	-3.1016850131041829	0.0650478317203768	0.2204661348183508	
+4.2309999999999999	0.0494358519612864	7.4201076562326653	6.4241978577501868	-3.1836152726217075	-0.0000856665115248	0.0003934304590623	
+4.2319999999999993	0.0407624831753974	7.4097158989001422	6.4437237106601097	-2.9860270083806495	0.0362327328578770	-0.0113131955237003	
+4.2329999999999997	0.0565750875640729	7.3824309521656994	6.4534088825591533	-3.4222256152853627	0.2310935514509936	0.2053588672230374	
+4.2340000000000000	0.0737349473925208	7.3310400043834374	6.4893651322452515	-3.1532266857189581	0.2231562668731743	-0.0816576096946343	
+4.2349999999999994	0.0530686896301519	7.3326603939705590	6.5333000324361379	-3.1447771778527334	0.0485012422242630	0.0643601850288960	
+4.2359999999999998	0.0643018332084602	7.3017326112948586	6.5425161428254412	-2.9382531825767177	-0.1687217753541257	-0.3372781896752293	
+4.2370000000000001	0.0529751629530542	7.2977154165046301	6.5523723661344908	-3.0768962493675063	0.1030486858015184	-0.0270646087879615	
+4.2379999999999995	0.0494916852452360	7.2860495340471614	6.5921776246858297	-2.8572423644904443	-0.0173768624354412	-0.0775952555730850	
+4.2389999999999999	0.0577952582646663	7.2592514372688397	6.6161130456177331	-2.9044008842453826	-0.3887123421801353	0.0819642887817355	
+4.2400000000000002	0.0665608486142681	7.2193791719009717	6.6284540033475636	-2.9292007403437248	0.0097805473990890	-0.0605933088559480	
+4.2409999999999997	0.0560899252247102	7.2181234694234915	6.6728551853719633	-3.1283991331710532	-0.1173518699706853	0.1066605097541983	
+4.2420000000000000	0.0744324474811667	7.1895788416455133	6.6793221630546071	-3.0110832514797572	0.0461731835947300	0.0309320062531781	
+4.2430000000000003	0.0582269472026353	7.1714692059216878	6.6952388335203077	-3.0872119127597264	0.1466485805229752	-0.2024695637671610	
+4.2439999999999998	0.0271956446011345	7.1359006366046804	6.7101884669367440	-2.9861920905120991	-0.0030188866538248	0.1180214942034256	
+4.2450000000000001	0.0580420729641919	7.1354703862329414	6.7138320629086703	-2.8001483881510105	0.2366726235650497	-0.2634376111930931	
+4.2459999999999996	0.0513906891102438	7.1115569359116648	6.7353350594349202	-3.3387544130686693	0.1611076344718751	0.0951294448286131	
+4.2469999999999999	0.0525895766699796	7.0799935604007498	6.7795249300155636	-3.0897355101412707	-0.0624821478449207	-0.0425910741643952	
+4.2479999999999993	0.0468815649738155	7.0658116688294825	6.7977385037391818	-3.1867908301938441	-0.1426327202595422	0.2372491858245613	
+4.2489999999999997	0.0601795696331901	7.0250442960759143	6.8230377934618414	-3.0174032507351276	0.0702916253627621	-0.1689446213879922	
+4.2500000000000000	0.0515415238318021	7.0016133727376548	6.8246047844512541	-3.0421697746450644	0.2126037181011628	0.1612836030867523	
+4.2509999999999994	0.0564718604999713	7.0104879019180997	6.8702479094937061	-3.0363901651189193	-0.0755240451067167	0.1933885291766059	
+4.2519999999999998	0.0669510804565568	6.9829202709767060	6.8965556775310519	-3.2249028836721743	-0.0697635846977165	0.1336730367766963	
+4.2530000000000001	0.0421478253793361	6.9488144848596560	6.9405516934417699	-3.1958920195951270	0.1497532986309904	0.0067445345429010	
+4.2539999999999996	0.0604212764519755	6.9283842998610394	6.9381639879657913	-3.0480089077409911	0.0110648082077741	0.0103469609874157	
+4.2549999999999999	0.0741067629338416	6.9220715300046409	6.9557726660093291	-3.0152351616365944	-0.1148069009575394	-0.0894360321331782	
+4.2560000000000002	0.0452860461962298	6.8901905211850840	6.9804786859518577	-3.1880977090517795	0.0339392429370680	0.2447456292098578	
+4.2569999999999997	0.0627633212735550	6.8698206991160164	6.9945161418684236	-3.1580451774832023	0.0582165511844325	-0.2214461862608164	
+4.2580000000000000	0.0488238680841823	6.8553880114846066	7.0257763304523531	-3.1674688826486217	-0.2746672468472803	0.1239570096690214	
+4.2590000000000003	0.0310556757375689	6.8231131727437901	7.0448306688980091	-3.0450594825901414	0.0933681367331585	0.0116229020763608	
+4.2599999999999998	0.0386986929361335	6.7955982010936484	7.0623105270372522	-2.8568979463701605	0.0368932662792943	-0.0862342610760982	
+4.2610000000000001	0.0426434811140886	6.7583999513262132	7.0969245268757319	-3.1216454908852125	0.0320606302548969	-0.0651826223954476	
+4.2619999999999996	0.0352873773225646	6.7443290566155145	7.1013401978098880	-2.9174256069958111	0.1696513516226137	0.0295616284759740	
+4.2629999999999999	0.0746734308327492	6.7568401239153957	7.1446716458362625	-2.9511640029452009	-0.1864053181355004	0.1430951969077292	
+4.2639999999999993	0.0702352118757525	6.7233157242130748	7.1692169275450794	-2.8707582477119526	-0.0028239331031413	0.1435152925235319	
+4.2649999999999997	0.0627728092699473	6.6810994283145249	7.1743911581474293	-3.0162358988721807	0.1420068822262170	0.1246114981524772	
+4.2660000000000000	0.0554761529339908	6.6713849579253033	7.2047053454199110	-2.9152364668215411	-0.0354968406417510	-0.2291716185882188	
+4.2669999999999995	0.0548506648710518	6.6466730360598545	7.2396256285022531	-3.1427121755036271	-0.0493837905364326	0.0461049313252570	
+4.2679999999999998	0.0379024918972091	6.6314483058330822	7.2408601830332717	-2.9737316246148859	-0.2799291314789261	-0.2187165036043167	
+4.2690000000000001	0.0490128728006895	6.6056209231852261	7.2805558673892934	-2.9276780590736440	-0.1062279755186364	0.0867421428832791	
+4.2699999999999996	0.0647225255749472	6.5509861585988594	7.2914906678218401	-3.2805897092298668	-0.0007846376276921	-0.0903067894113486	
+4.2709999999999999	0.0596390701538404	6.5583112151268992	7.2961207626201112	-3.0816355164612621	0.0480858875694663	0.1691339602337618	
+4.2720000000000002	0.0511882077141960	6.5264765441739474	7.3133785625252949	-3.0002285459042826	-0.0781542962928176	0.1086622327994525	
+4.2729999999999997	0.0640151573026832	6.4879847637418644	7.3258871513599573	-2.8162122909047005	0.0077858855559987	0.1287178966800009	
+4.2740000000000000	0.0579328323263438	6.4656770299729258	7.3460725857854241	-3.2299870352432900	0.1301015697361384	-0.0370356711396346	
+4.2750000000000004	0.0572836103107501	6.4765281090125235	7.3806998026235551	-3.4221773600209504	-0.2385779550389159	0.1581500966059355	
+4.2759999999999998	0.0422253550819177	6.4467717134372311	7.4216310235218845	-3.0405466872522058	-0.2281726765507865	0.0308785434369952	
+4.2770000000000001	0.0703478862950174	6.3968527333520395	7.4202310602241583	-3.3521749968244361	-0.0408220833155048	-0.0704860122038832	
+4.2779999999999996	0.0644410505935112	6.3807242421788546	7.4465350883441932	-3.1551310483400057	0.0565547372543831	-0.1102317533228923	
+4.2789999999999999	0.0620538304140572	6.3648722681403287	7.4572827608943433	-2.7666349568368802	-0.1025220349208291	0.3350663485637047	
+4.2799999999999994	0.0585476705244255	6.3256799379857815	7.4772696765624698	-3.0187398138511417	0.2696010158487160	-0.0942133494141883	
+4.2809999999999997	0.0418052422780153	6.3285218432848129	7.5067127319952753	-3.1715437096093240	-0.0448172878927116	-0.2227511961966713	
+4.2820000000000000	0.0594435308960847	6.2953461002814608	7.5217394326515379	-2.8566295039331822	0.1019253758152199	-0.0251247471817092	
+4.2829999999999995	0.0591922898638454	6.2708775292974783	7.5408431815683912	-3.1597996871042855	0.2125546126969097	-0.0289380513372076	
+4.2839999999999998	0.0855700420268231	6.2386291152570612	7.5615265896808532	-3.2234449904804889	0.0963232856977874	-0.0603574773145288	
+4.2850000000000001	0.0511686378136133	6.2258819219665487	7.5852364945917854	-3.2824345599343947	-0.1790504296967010	0.0333415923154531	
+4.2859999999999996	0.0541473527933152	6.1975010392160801	7.5974325845156470	-2.9827404586763251	-0.4411511059795246	0.0498025936220998	
+4.2869999999999999	0.0659471941288022	6.1733966167200993	7.6084519060605560	-3.2988274274597340	0.1945710185167700	0.2526022861765065	
+4.2880000000000003	0.0522393620021914	6.1425137691394065	7.6217147434030883	-2.9614144359033938	-0.1699630216635202	0.1162147425419823	
+4.2889999999999997	0.0434223091631705	6.1159034984234353	7.6523045532661547	-2.8658589831135224	-0.0504508520967908	0.0275618074413357	
+4.2900000000000000	0.0513602530231031	6.1092197661085281	7.6988954538174843	-3.2631011886513464	0.0267919120815214	0.0488144940797624	
+4.2910000000000004	0.0781443451772084	6.0720153578859746	7.7183206727770175	-3.2824067539931536	-0.3317466906722464	-0.1120676865740208	
+4.2919999999999998	0.0641151716123688	6.0493637807636880	7.7277355722883421	-2.9579478216443049	-0.0542489701187283	0.1175104413329973	
+4.2930000000000001	0.0552458514144196	6.0415614816028196	7.7225184945157936	-3.3681625223978875	0.2142259640742884	0.2687832444457402	
+4.2939999999999996	0.0549994957497511	5.9995465029238559	7.7659052845580137	-3.0689467086027711	-0.0691933846660231	0.1942127630481443	
+4.2949999999999999	0.0444345698315195	5.9935748355382055	7.7534151811928318	-3.0553011334666396	-0.0408164812783736	0.0401557265599429	
+4.2959999999999994	0.0496380220573599	5.9508436209222149	7.7840355565894699	-3.1633279701682495	0.1485208293824585	0.0413628382212840	
+4.2969999999999997	0.0393620087123402	5.9334332575737436	7.8251397222860080	-2.9919786909972133	0.0061675911674841	0.0827148350211923	
+4.2980000000000000	0.0616887296193762	5.9089542289380566	7.8252880076267388	-2.9608917417966891	-0.0263408076429305	-0.0336299999411514	
+4.2989999999999995	0.0422046647133287	5.8817072282655776	7.8227894029666185	-2.8513128020837799	-0.0139607342836090	0.1884517934184003	
+4.2999999999999998	0.0553137311350000	5.8756317367819966	7.8696800210752169	-2.9545143927609843	0.0143565975811767	0.0326704034356735	
+4.3010000000000002	0.0658764638240815	5.8359294252218401	7.8710874541601639	-3.0748782426870531	0.1525245233252809	-0.0535654898065422	
+4.3019999999999996	0.0661615781456748	5.8217295465482630	7.9014203391884008	-3.1249941523247764	-0.3403108973698544	0.1898349890566488	
+4.3029999999999999	0.0588411030722690	5.7684992282260179	7.9026997470329050	-2.8628439217061499	-0.1058233427183554	0.0385346052885381	
+4.3040000000000003	0.0456261092368143	5.7652487334085674	7.9042001240033803	-3.0130973718648151	-0.1508536156620042	0.2037199577111860	
+4.3049999999999997	0.0725678197662060	5.7130193894044350	7.9491929209316226	-3.2163185025959504	-0.0509173260158235	0.0767031552897335	
+4.3060000000000000	0.0588365632998594	5.7044134490754548	7.9824616446867429	-3.1585285453465515	0.3257618850628773	0.1040796577077143	
+4.3070000000000004	0.0789543531860459	5.6608972364582195	7.9979005852427170	-3.0409456022420041	0.1531456656537462	0.2240597881773946	
+4.3079999999999998	0.0604032277401944	5.6587145737145930	8.0226112957025180	-3.2432210796772378	0.0893813009812839	0.0519674963805226	
+4.3090000000000002	0.0617681166689349	5.6474009495742798	8.0237986593997235	-2.9421911391321709	-0.1515018490238745	0.2675099565835183	
+4.3099999999999996	0.0525323035320105	5.6144578844661304	8.0373677076479844	-3.0821981366183735	-0.0693436876941471	0.0136435844695464	
+4.3109999999999999	0.0553826162713215	5.5809903848078504	8.0501691101228836	-3.2259351680020099	-0.0919170608419434	0.1295061937989001	
+4.3119999999999994	0.0525996689662740	5.5414539584317346	8.0662943777505394	-3.1185770856617832	-0.0263481136751888	0.0337118515088760	
+4.3129999999999997	0.0656626680853487	5.5110551378289570	8.1030494439586072	-3.0832097130109419	-0.1877266365783640	0.3245050953203929	
+4.3140000000000001	0.0630345142516468	5.5080140125523069	8.1345060986193758	-3.2727315378812696	0.0113323461545863	-0.0889684621485290	
+4.3149999999999995	0.0573760002642494	5.4966770684721968	8.1339648812309537	-3.0119631665887505	-0.2194313033237211	0.1662167093999204	
+4.3159999999999998	0.0302332038931013	5.4645339039751422	8.1390322592328754	-2.9640841748260174	0.0910350124921088	-0.1293978445012673	
+4.3170000000000002	0.0727887385389877	5.4234741538790763	8.1534328965610978	-3.1147600554601862	-0.1346327625005615	0.1532845832063353	
+4.3179999999999996	0.0411478260059306	5.4072679033149758	8.1699846508804796	-2.9930543766152828	0.1915664362035310	0.2106166911702803	
+4.3190000000000000	0.0526349261805079	5.3746020145719582	8.2095879593091041	-3.3106643738961266	0.0132864027808241	0.1584494994571838	
+4.3200000000000003	0.0589182020755586	5.3462504884660431	8.1982788861858342	-3.0692893781725141	0.0174554163253740	-0.1814328249604408	
+4.3209999999999997	0.0445532267658692	5.2972420026295914	8.2361810748845432	-3.1982079035913209	0.0476532392967222	0.0005657713037784	
+4.3220000000000001	0.0378061596301680	5.3106709295181371	8.2345336159096920	-3.0156889921392205	0.0190633269189487	0.0606776849764906	
+4.3230000000000004	0.0818842854434497	5.2695616608588329	8.2588833874543184	-2.8791675101549452	-0.3765073641997080	0.2756456822562907	
+4.3239999999999998	0.0570162885738573	5.2519408048422216	8.2793870538959133	-3.0989615356359286	0.0218452037412444	0.0741381952476822	
+4.3250000000000002	0.0590436249105909	5.2144880073419175	8.2930401194859424	-3.0774171676190445	0.0269992925569847	-0.0253132218539343	
+4.3259999999999996	0.0490897666085439	5.2051144368889872	8.3136418070814546	-3.1649348252001013	0.2009310653375514	-0.1104968240083661	
+4.3270000000000000	0.0530714207010018	5.1618582682099206	8.3102949871590504	-3.0358043606222722	-0.2044953279997343	0.1191468775385715	
+4.3279999999999994	0.0419782658829101	5.1593546620562964	8.3384281473610535	-3.0391493648500574	0.1412352649779489	0.1906979026617969	
+4.3289999999999997	0.0704572644609069	5.1238721061273180	8.3678534339978405	-3.0966776996018295	-0.0417172705523159	0.1979405781728286	
+4.3300000000000001	0.0564047820462872	5.1011840389766840	8.3832369214620215	-3.0180878777345472	0.2542286760915730	-0.0911823549071268	
+4.3309999999999995	0.0529128831845845	5.0491528254977256	8.3986558481420897	-3.2735814040503177	0.0954932818822495	0.1891274312693631	
+4.3319999999999999	0.0381134887116064	5.0336553679532736	8.4291093401772486	-3.2252266721195166	-0.0223326635440828	-0.0157447059479684	
+4.3330000000000002	0.0531247927182094	4.9971075226773758	8.4272774636422962	-3.2055605504116347	-0.1191975207299925	-0.0607914127004051	
+4.3339999999999996	0.0369672741991157	4.9710158635001811	8.4238728017508944	-3.0402695235055273	-0.1933989441489869	0.0502925793283956	
+4.3350000000000000	0.0593149490664115	4.9443353099218577	8.4616020120501361	-3.2718258860829095	-0.0339457928093921	0.1215353666751375	
+4.3360000000000003	0.0609856142872562	4.9486666501015435	8.4618499128954969	-2.8224588917024942	-0.0658874292847156	-0.1875483658136294	
+4.3369999999999997	0.0559203767793320	4.8942111974275262	8.4802412150054405	-3.0102637185886549	0.0598705062208222	0.1123903450688332	
+4.3380000000000001	0.0754631675652468	4.8595713132641176	8.4871233863374194	-3.0995535043638287	-0.1033359653667536	0.2096084336207774	
+4.3390000000000004	0.0323185412104655	4.8378745341047518	8.5191902546707787	-2.8253625936985598	0.0500445139992051	-0.0188636656971906	
+4.3399999999999999	0.0550541768838424	4.8143532571733489	8.5303718138465658	-3.2452006296576634	-0.2106647884846824	0.1677595943141419	
+4.3409999999999993	0.0438463736784463	4.8095413565875180	8.5484218121250990	-3.1776512987714582	-0.1157398561466650	0.2143256086730264	
+4.3419999999999996	0.0555811496204749	4.7683564781358809	8.5631088383218703	-3.2573146813513567	-0.2263361769612010	-0.0252450314269047	
+4.3430000000000000	0.0831778152092974	4.7541449808519225	8.5823367761060432	-3.1934137610585935	0.2207580029206052	0.1761588902062861	
+4.3439999999999994	0.0421201154300599	4.6945929222703935	8.5892211726630503	-2.9424883638992334	0.0716586826787600	0.1388628546655331	
+4.3449999999999998	0.0731866757385670	4.6894294611400067	8.5999848947036881	-3.2334701403266672	0.2305356518807549	0.2463016078718143	
+4.3460000000000001	0.0597312041617732	4.6528961162287619	8.6088203511819135	-3.0883171945822760	-0.0023880333690801	0.0301061282686382	
+4.3469999999999995	0.0428738127634441	4.6180700662594205	8.6300760764364881	-3.0541221415761943	0.0696744602343603	0.1486568559021472	
+4.3479999999999999	0.0289889144891319	4.6140271804411412	8.6690318337709940	-3.1471387493668694	-0.0306272571939216	0.1877017198589978	
+4.3490000000000002	0.0574568104873286	4.5972529226615224	8.6886752991561789	-3.1937144028242330	-0.0718706757833986	-0.1000758942625182	
+4.3499999999999996	0.0614019903149512	4.5554842741117181	8.6718714463378017	-3.2728511913959042	0.2068364123343880	0.1580204730055540	
+4.3510000000000000	0.0397802176930618	4.5317696593523609	8.6804374855007111	-3.1115248885420601	-0.2784043618566137	0.2204534790281859	
+4.3520000000000003	0.0494911805399811	4.5216785554846375	8.7163289008968974	-3.2577366861611048	0.1392145696503310	0.0238016049716790	
+4.3529999999999998	0.0428617110140018	4.4649828942938328	8.7248495711003109	-2.7507334753730608	-0.1542899399406668	-0.0883149688336803	
+4.3540000000000001	0.0588445365512421	4.4493675012597320	8.7257419939503702	-3.2493536292288741	-0.1021606392910285	-0.0871063154278881	
+4.3549999999999995	0.0600297264640380	4.4263743751040856	8.7366055456390459	-3.0154099472553249	-0.0951826580490786	-0.1015318538308875	
+4.3559999999999999	0.0592036867162772	4.3905086869495111	8.7653864620527226	-3.0706064262936636	0.0038857779870354	0.0849220741248179	
+4.3569999999999993	0.0625689122648121	4.3786080037090098	8.7978160832901580	-3.2908462216457592	-0.0034702038881854	0.0084039505954087	
+4.3579999999999997	0.0776070399296625	4.3407001074810214	8.7883987644122961	-3.1075498328071958	-0.0769869809617715	0.2477384810977766	
+4.3590000000000000	0.0614675615924797	4.2897718203699391	8.8042225438271213	-3.0149083286382230	-0.1887554427470511	-0.0464542374101941	
+4.3599999999999994	0.0572702371517189	4.3036738148095770	8.8216370748953548	-3.4972077389617708	0.1713979207178564	-0.0637698643597717	
+4.3609999999999998	0.0460889869897479	4.2431586175257499	8.8204532146370322	-2.9436074396995386	0.1004529277643266	0.1403809709493115	
+4.3620000000000001	0.0719635197482658	4.2385877073861629	8.8267109772507162	-3.0460363698422670	-0.0109291420761407	0.0082600828446094	
+4.3629999999999995	0.0915213606846984	4.2016215592155257	8.8709870771473138	-3.1611499411312001	0.1984302112026291	-0.1048662826808819	
+4.3639999999999999	0.0468979613632063	4.1522555838035169	8.8566969576040595	-3.1671635259523985	-0.0588856025040823	-0.0828354960470482	
+4.3650000000000002	0.0551372352670865	4.1482996109759949	8.8835540695289748	-3.5367083677397875	-0.1868745728923323	0.1519729895358968	
+4.3659999999999997	0.0677932781380814	4.1196614399186764	8.8960507386162977	-2.8957437085154041	-0.2122478353022019	0.1686822072651494	
+4.3670000000000000	0.0489606442633129	4.0719296794353648	8.9282826940070965	-3.2847853895055783	-0.1061464383379272	0.1554083160246204	
+4.3680000000000003	0.0483037479179525	4.0635004977452791	8.9236403780991704	-3.1613055475127880	-0.1759037268664127	0.3691724124840065	
+4.3689999999999998	0.0765105260050608	4.0301445889334078	8.9269048220597345	-3.0155721851400537	-0.1837037809561006	0.3256312285511757	
+4.3700000000000001	0.0546857819421671	3.9967379078471290	8.9374452013701493	-3.2712766887523732	-0.1322836954321719	-0.0896362295285563	
+4.3709999999999996	0.0574026953114057	3.9796712794439513	8.9555108458864865	-2.9082301523166105	-0.1406660942484905	0.3853038712334048	
+4.3719999999999999	0.0731542882142347	3.9552556684743019	8.9737853312433540	-3.1923397943316161	0.1976495537362130	0.0379415089022730	
+4.3729999999999993	0.0536427916421545	3.9012097145140165	8.9774942429684170	-3.1259471690493985	0.1866377741064476	-0.0772795745833251	
+4.3739999999999997	0.0696142862078859	3.8964825486687240	8.9900419930268125	-2.8838410594721862	0.2960004324007249	0.1236953667944217	
+4.3750000000000000	0.0645137626317997	3.8683425334343720	9.0071991865474317	-3.0102137247613601	0.1179179793307231	-0.2087896069055277	
+4.3759999999999994	0.0338985172457419	3.8302614083208479	9.0235044040647985	-3.1990386914177562	-0.2417760015437103	0.0537153524597066	
+4.3769999999999998	0.0510522251740064	3.8225788370285576	9.0179071242535827	-3.1209849601966582	-0.2714874691116483	0.0210679081238286	
+4.3780000000000001	0.0592462081902946	3.7864633055032568	9.0368203092596282	-3.1562252356868350	0.0755980139646695	0.1468174044200507	
+4.3789999999999996	0.0707305522747337	3.7500044592833217	9.0573288343267073	-3.1711606495862203	-0.1347241998240580	-0.0848487137060520	
+4.3799999999999999	0.0706447116638610	3.6922598084086498	9.0501936436214443	-3.2587874415889413	0.1914844127462553	0.3381484993765056	
+4.3810000000000002	0.0512445583893457	3.6752753548621802	9.0592058915758891	-2.9194054412349817	-0.1874541146796432	-0.1112572315873589	
+4.3819999999999997	0.0707603444896949	3.6675345815184799	9.0979115501622232	-2.9751034937628580	0.1855014867626543	0.1344043888233336	
+4.3830000000000000	0.0480297628545361	3.6215946196618134	9.1109168075831963	-3.1629610165883832	-0.1708215519967798	0.3236657282016909	
+4.3840000000000003	0.0657871204331323	3.6052955272569638	9.1101991792721400	-2.9913969451398690	-0.1773278215483688	0.2653418130834767	
+4.3849999999999998	0.0631908045857981	3.5784082733030833	9.1036499665404182	-2.9427287204147579	0.0091861005797944	0.1828359195349373	
+4.3860000000000001	0.0651715329129621	3.5484638831004824	9.1312951633007593	-3.2300418102534421	-0.0745152716297404	-0.0384579592247015	
+4.3869999999999996	0.0717075496724734	3.5285834703700050	9.1369043680705069	-3.2433169594476632	-0.1476511251169218	0.1775714159575664	
+4.3879999999999999	0.0489823489784918	3.4721727876998032	9.1621694404386655	-3.1394091025913955	-0.4159894238771703	0.0086901004050602	
+4.3889999999999993	0.0788338817002590	3.4658096172114101	9.1664165751589675	-3.0237806417733286	0.0275577494813257	-0.1076507721042377	
+4.3899999999999997	0.0622905596507099	3.4236510079643208	9.1971808724670865	-2.9995192126468755	-0.0414933887225718	0.3479139407102097	
+4.3910000000000000	0.0649687232904887	3.4120983165474721	9.1839273122187723	-3.1035384555862939	-0.1391483964356507	0.1836917284971464	
+4.3919999999999995	0.0403886017418926	3.3679888471274597	9.1939480153544206	-3.2164510593355722	-0.2232559413170492	-0.0784766442154721	
+4.3929999999999998	0.0724547237775786	3.3515107306440601	9.2002217124439625	-3.2750572357551451	-0.2335584359774414	0.1020625674943838	
+4.3940000000000001	0.0494412943493379	3.3135482078780587	9.2177721608863461	-3.0099541325613619	-0.3620747096100564	-0.0109675008527441	
+4.3949999999999996	0.0525511432133752	3.2829016156070185	9.2211555798208469	-3.1896870402357140	-0.1808097843150881	-0.0453549772305787	
+4.3959999999999999	0.0570411415795652	3.2327833858121693	9.2562896089100306	-3.2307166765260167	-0.0609383501000104	-0.0264322269626343	
+4.3970000000000002	0.0555479622170012	3.2409801317543385	9.2501597632840173	-3.0734148026284100	-0.2089594676303307	0.1574683147073496	
+4.3979999999999997	0.0462811049497267	3.1964182283306273	9.2527143975945609	-3.1237821845030811	-0.1198977433445342	-0.0235969286214184	
+4.3990000000000000	0.0465460100817174	3.1662557805450193	9.2602781601143818	-3.0384587301221759	0.0580187866031723	-0.0835525717573507	
+4.4000000000000004	0.0580130462639937	3.1249381915220087	9.2723834027241168	-2.8708964949837519	0.0611023353961076	0.1406549119379411	
+4.4009999999999998	0.0523400847643706	3.0942842404438919	9.2954031659354897	-2.9211545893243018	-0.0096030455182470	0.0744354732213233	
+4.4020000000000001	0.0496374263061514	3.0894476971464888	9.2920658223965038	-3.0649272736633817	-0.0739224986071517	-0.0446373744912521	
+4.4029999999999996	0.0574151132641111	3.0702666846426343	9.3336014792551047	-2.9436289129970916	-0.1343954211725563	0.1382845660896569	
+4.4039999999999999	0.0586204089075053	3.0232899523135686	9.3239935719087956	-2.8844080174350317	0.2082611757873257	0.1979021778626433	
+4.4049999999999994	0.0487337281483805	2.9985936843195091	9.3399302031573725	-2.8496272294786951	0.0787053022033286	0.2281723731550268	
+4.4059999999999997	0.0537319710377675	2.9882404265268145	9.3508062345575844	-2.8670072185175277	-0.0894127257695662	0.0830552079562000	
+4.4070000000000000	0.0416486001080856	2.9174080781854270	9.3360004105781407	-3.1063508936271971	0.0793317602696469	0.0026355030557138	
+4.4079999999999995	0.0358806810827144	2.8957050209869086	9.3635676502601104	-3.1120667661607442	0.0135211676930144	0.2048069987346411	
+4.4089999999999998	0.0429340497471311	2.8700912664187448	9.3546944786067137	-2.9842672945879225	-0.0894001439270681	0.2614242316474542	
+4.4100000000000001	0.0475894763879541	2.8503644986154097	9.3843868184711319	-2.9755037742595487	-0.1531995669943094	0.0864104276852192	
+4.4109999999999996	0.0458408026073227	2.7912135390048909	9.4014326479194352	-2.9063723938394799	-0.0028736254681254	0.0383019396382576	
+4.4119999999999999	0.0659292805572625	2.7845236634706914	9.3865427672728021	-3.0573866873588131	-0.1198571681267784	0.0484951135669440	
+4.4130000000000003	0.0301904025989965	2.7569669021827776	9.3964689010284541	-3.1815720251510258	-0.0497491627486164	0.2265800388615115	
+4.4139999999999997	0.0429168460056840	2.7401601276815133	9.3976871495048719	-2.8175385849817176	-0.0573563514442439	0.1652436372314478	
+4.4150000000000000	0.0624787362704274	2.6742353356228805	9.4142411732422318	-3.2442660815161743	-0.0219379206020263	0.3980945780031126	
+4.4160000000000004	0.0755099029992962	2.6630519163035227	9.4391725983846122	-3.0860950669935985	-0.1284532819634580	0.0574375071302753	
+4.4169999999999998	0.0606281136833617	2.6094015015998977	9.4466737137035359	-3.1159621489225717	0.0624729327851238	0.1588466699026348	
+4.4180000000000001	0.0584428815542882	2.5948365257615351	9.4523558069782840	-3.1544148000186603	-0.2993051436786214	0.2735425205321941	
+4.4189999999999996	0.0598414290250657	2.5733788797587014	9.4344535782306238	-2.9794394597823359	0.1058753705903694	0.1375244553770750	
+4.4199999999999999	0.0499669912837392	2.5582477066021778	9.4582284370474987	-3.1984476657129486	0.0107570072987037	0.1266103742425814	
+4.4209999999999994	0.0407078151654473	2.5015106435939698	9.4694898651792538	-3.1417664931726561	0.1402827309319575	-0.1935274706446405	
+4.4219999999999997	0.0667699237114294	2.4994612969973709	9.4718417780452064	-2.9150639487783505	0.0292804337444004	0.0840382842314973	
+4.4230000000000000	0.0605489788412448	2.4567703588828929	9.4950799396362751	-3.0307350144756029	0.1885433191309247	-0.0979714478201138	
+4.4239999999999995	0.0641594215413872	2.4386306347148428	9.5023246558607930	-3.2178392589611353	-0.0678919899458476	0.1853968841423065	
+4.4249999999999998	0.0601573614979002	2.3780926717654487	9.5048828297996781	-3.2269947051035688	0.1158955873395960	0.2445368951633877	
+4.4260000000000002	0.0515249905094660	2.3761695524570965	9.5164713533758167	-3.1847205907341016	-0.1020331193765254	0.1190470621394831	
+4.4269999999999996	0.0572521555561893	2.3299217767614695	9.5054693120698008	-3.0853606161387659	-0.0416207354467418	0.0302359733938792	
+4.4279999999999999	0.0900050530410005	2.2974110202288216	9.5147019378995150	-3.4169154133329975	-0.0074751957432930	0.2277517823597091	
+4.4290000000000003	0.0620650790982186	2.2786024982542825	9.5405136380863862	-3.1400728146093573	-0.0975014388113151	-0.0082026843124468	
+4.4299999999999997	0.0711889069368146	2.2643271588024088	9.5124317934068525	-3.1635572320551359	-0.2371251852977260	0.2263850522512894	
+4.4310000000000000	0.0490314896716981	2.2117233834170045	9.5355168710118026	-2.8254073918282057	0.2920606160009329	0.3870496842002604	
+4.4320000000000004	0.0488374992255103	2.1937486089040519	9.5557993720035483	-3.0555813887512957	0.1051957697140913	0.3020597169351257	
+4.4329999999999998	0.0717119633243861	2.1438445190460031	9.5537792845011893	-3.3057148708959239	0.1181265816249180	0.0869418895029965	
+4.4340000000000002	0.0563503694673492	2.1177402929691955	9.5461659849914238	-3.0376592111981511	0.0484335408403879	0.2055212573308406	
+4.4349999999999996	0.0433821189519095	2.1035300227386475	9.5408828524514444	-3.3591180122200042	0.2846893764951000	0.0504653269180840	
+4.4359999999999999	0.0392526272524417	2.0634907815349024	9.5704751348653812	-2.8844276125776616	-0.3225200031854984	-0.1875411035576562	
+4.4369999999999994	0.0618524404857314	2.0313177324613454	9.5768673438975380	-3.1631532073142061	-0.0797765345198425	0.0340814265244437	
+4.4379999999999997	0.0553730421272603	2.0030023330292384	9.5723518019892193	-3.0657949803127913	0.1150936110376811	0.2210091886886745	
+4.4390000000000001	0.0595909798564799	1.9968494641251084	9.5952969181912824	-2.9760431273007235	-0.2768696485576104	0.1735587368377239	
+4.4399999999999995	0.0583840125149293	1.9291268838680993	9.6041969187074017	-2.7799890853173728	0.0393181593155715	-0.0292852547551546	
+4.4409999999999998	0.0827884961934419	1.9107151854487392	9.6127934890029518	-3.0907705269394530	0.0484078029567093	0.2747671786576316	
+4.4420000000000002	0.0691856827526636	1.8896250557434544	9.6207413823442938	-2.6518032523278841	-0.0588150165888860	0.2200392099952174	
+4.4429999999999996	0.0499119416279730	1.8812028644885685	9.6171253574790594	-2.8994240308536119	0.0712973395555814	0.0804597626272478	
+4.4440000000000000	0.0600394284281263	1.8327850196739668	9.6052102835024744	-3.0118529723101637	-0.1190172281589980	0.3973396551965305	
+4.4450000000000003	0.0667307120900154	1.8003228152970838	9.6371662067183035	-3.0874968408264167	-0.0779171499160846	-0.0082415646506465	
+4.4459999999999997	0.0450890731076831	1.7613909960170069	9.6430730635306361	-2.9566686303963983	0.3049127146923694	0.0466837084215366	
+4.4470000000000001	0.0584512381550188	1.7444894737646284	9.6198865073840736	-3.1013004189669799	0.0638601984974175	0.2658375546125824	
+4.4480000000000004	0.0337436470942739	1.7182803578109469	9.6443833907210834	-2.9874381746998462	0.1858512660258645	0.1291643726673444	
+4.4489999999999998	0.0554762841909816	1.6759694306412429	9.6434733366398646	-3.1732640327499935	-0.0278851017979124	-0.2473073734715739	
+4.4500000000000002	0.0488547909304048	1.6558614758847026	9.6392496466711322	-3.0096805877107156	-0.0177995180316352	-0.1510236677616588	
+4.4509999999999996	0.0658031168782007	1.6023133034633028	9.6582115505515898	-2.9300549230115118	0.0307297970783288	0.3044668578364934	
+4.4520000000000000	0.0605014314952475	1.5763724446369596	9.6729109715579096	-3.0704065680755890	0.2744659991610204	0.1151491326571637	
+4.4529999999999994	0.0543288568548743	1.5276472279524929	9.6610240965980374	-2.9238105017575089	0.0282719015573657	0.2537874888930357	
+4.4539999999999997	0.0685689513897429	1.5340526423888845	9.6823521080104769	-2.9387484241955093	-0.0833209183973144	0.1720506266494713	
+4.4550000000000001	0.0462218614761907	1.4966661657487168	9.6696035664134445	-2.8419837095076597	0.1935413922078628	0.3654182412502996	
+4.4559999999999995	0.0577207486525742	1.4627476326819393	9.6955693662865716	-3.1654145946525034	0.1749851924699688	0.0372673980656802	
+4.4569999999999999	0.0650185267724649	1.4213575525351962	9.6866380301500392	-3.2639424813236957	0.0913919293831453	-0.0209950566960653	
+4.4580000000000002	0.0508959198422983	1.3980922693473832	9.6673219928905780	-3.2304807683294934	-0.1877690863874640	0.1105453134889665	
+4.4589999999999996	0.0630746141236571	1.3857900528104550	9.7095100297947319	-3.3052511759870251	0.1446992045979962	-0.0080203168894565	
+4.4600000000000000	0.0644328313119843	1.3497729239284935	9.6885473629333134	-3.1136873444646489	-0.1740926766833763	-0.0015318118074506	
+4.4610000000000003	0.0508172713535609	1.3292343264718971	9.7059379141050979	-2.8710064744903621	0.1107088461532246	0.4702361030095427	
+4.4619999999999997	0.0361876837243459	1.2847540639602109	9.7075833494629897	-3.4857700017451561	-0.6140967070762235	0.2161308637573534	
+4.4630000000000001	0.0481496088290125	1.2193587211480215	9.7058682564997696	-3.3054305555817036	-0.0495081349746987	0.0935925243120939	
+4.4640000000000004	0.0617970522592234	1.2109675751014164	9.6987105227515009	-3.1541232081131132	-0.0996544167045492	0.0417964175745363	
+4.4649999999999999	0.0561083259947168	1.1757733394841250	9.6963660307151631	-3.2535006656853187	-0.1715561137898298	0.2101770121990327	
+4.4660000000000002	0.0536306559147638	1.1706110045515368	9.7287813388437598	-3.1403599661370363	0.0051080830613123	0.1364144489296603	
+4.4669999999999996	0.0651697772653159	1.1214769769392685	9.7147048156186209	-3.0027976262615201	-0.0011971766970876	0.0324040386673675	
+4.4680000000000000	0.0516068473384707	1.0730864506760582	9.7163477638861266	-3.1525756415243666	0.1695924799645386	0.1557517929189103	
+4.4689999999999994	0.0550534901351441	1.0843211848079055	9.7259413339977545	-3.1611041686837855	0.1736530603088058	0.0903908530364074	
+4.4699999999999998	0.0521633293826794	1.0333204742238313	9.7352264628949730	-3.1248581028980067	-0.0930603413263388	0.0752714612931427	
+4.4710000000000001	0.0464770580623793	1.0065235182351731	9.7371349320798632	-3.0768115621429035	0.0797288970763239	-0.2798098585770729	
+4.4719999999999995	0.0283161957178647	0.9754198823903112	9.7475234869561493	-3.2316392326671006	-0.2427086391782635	0.1345287186894122	
+4.4729999999999999	0.0532963568167651	0.9626470766185256	9.7474840351427634	-2.7529616028187567	0.0091441863075859	0.0629843334598849	
+4.4740000000000002	0.0433139420558530	0.9161485125375031	9.7612809703341998	-2.8600272589018196	-0.3071160563292645	-0.0027697323175310	
+4.4749999999999996	0.0730223218708828	0.8697832953658445	9.7577582890961647	-3.3603520635817326	-0.2653706871797901	0.1307044325848143	
+4.4760000000000000	0.0452031011006870	0.8374694246898058	9.7438654030352225	-3.3157709186251627	-0.3733475669071274	0.1675791900620756	
+4.4770000000000003	0.0660049649697174	0.8220712532886912	9.7678258637008781	-3.0150725863076131	0.1232349331037896	-0.0327644265623160	
+4.4779999999999998	0.0634636208638118	0.7899622675950064	9.7622413081317383	-3.0776274547919096	0.1640250634402870	0.0520660500918534	
+4.4790000000000001	0.0559031774485340	0.7407959159393902	9.7506724011450796	-3.1776985857423239	-0.2783742405902464	0.0105754903947500	
+4.4799999999999995	0.0590185748897250	0.7445405393047405	9.7480404336473203	-2.8701900260949955	0.0085067081784749	0.0451625534606249	
+4.4809999999999999	0.0573842577918719	0.6928327467088187	9.7575934778135540	-3.0585819342430525	-0.1822954298447270	0.0146999538335554	
+4.4819999999999993	0.0739673520973665	0.6727838859834245	9.7662519847553106	-3.1311767946825468	-0.2182909687001386	0.0232530746131322	
+4.4829999999999997	0.0577186900160557	0.6252295657584828	9.7761057070123396	-3.0806239547230745	0.0750580914194694	-0.1809281094094770	
+4.4840000000000000	0.0427736156353706	0.6311963990174608	9.7919714225498282	-3.0354011521436952	-0.0269797785165789	0.0304327077587384	
+4.4849999999999994	0.0398191053470840	0.5740086632380229	9.7615322890331893	-3.0852348420107494	-0.1201730943574426	0.0676648962233531	
+4.4859999999999998	0.0715006195456603	0.5451840431605617	9.7938116618721214	-3.0584866895092495	-0.0784835750279146	0.0681898015507266	
+4.4870000000000001	0.0488945567733438	0.5248534017599656	9.7547374845985217	-3.1623756415928383	0.0419856572728857	-0.0211999627477955	
+4.4879999999999995	0.0480362830095661	0.4941781819147675	9.7850495579864596	-3.1275521855604831	0.1012636945249027	0.0033588938568298	
+4.4889999999999999	0.0597092367785816	0.4535375052404694	9.7731102571286463	-3.0516319397207905	-0.1078979002460211	-0.0299007592545600	
+4.4900000000000002	0.0559002945447711	0.4083475392282950	9.7765950634578171	-2.8921576412857815	0.2212954107632160	0.1141377972514587	
+4.4909999999999997	0.0706740807760251	0.3906573939204483	9.7532009133361370	-2.7500197152294432	-0.2058521360117655	0.0041504644272381	
+4.4920000000000000	0.0713802628844058	0.3600469875568546	9.7799851166814271	-2.9853091930476632	-0.1069130259071990	0.2717543408320189	
+4.4930000000000003	0.0722797280489764	0.3293160951996729	9.7876094348341685	-3.2357183610054090	-0.1066138659842876	-0.0997924884409749	
+4.4939999999999998	0.0769509224236268	0.3131691066734190	9.7795418413391069	-3.0762794344500199	-0.2091189636934100	0.1409945543056356	
+4.4950000000000001	0.0501492488418007	0.2688242485132911	9.7837613097665113	-3.2236155545572065	-0.2696932122369661	0.1604130754212766	
+4.4959999999999996	0.0570037022660395	0.2474065261205923	9.7908566305793308	-3.0392267404646960	-0.1556193334237219	0.2439802471754568	
+4.4969999999999999	0.0549299314844664	0.2111194006276905	9.7793514475962056	-3.0585285223687757	0.0133513138565278	-0.1683693857878024	
+4.4979999999999993	0.0520170875573598	0.1781558167286214	9.7714876296274742	-3.0979227425731382	-0.2197038284751961	0.0687552068188824	
+4.4989999999999997	0.0383428776662771	0.1621595901026295	9.7804012288004678	-2.7799846050599553	0.0782633862865204	0.1591011090226724	
+4.5000000000000000	0.0605912396933459	0.1111368554926728	9.8014991828135987	-2.9886282705636074	0.2329480736202057	-0.1995827359579200	
+4.5009999999999994	0.0611246172369732	0.0958672612002021	9.8043348136570039	-3.3332041426024577	0.0294748186310794	0.3060102673299299	
+4.5019999999999998	0.0646134464921770	0.0550199932447338	9.7993063186231524	-3.2748078172308617	0.2545640340965365	-0.1457866397433125	
+4.5030000000000001	0.0541568606207233	0.0214891005243873	9.7854014541322716	-0.2348237027600124	-0.2102427512844795	0.1749793598698985	
+4.5039999999999996	0.0771643649782586	0.0129620742411857	9.7804901468398100	0.2621228469068608	0.1457375983275570	0.1691875396447438	
+4.5049999999999999	0.0554346941162199	0.0445554907070768	9.7594333070320722	0.2672648294750463	0.1740842531875741	-0.1564495915997026	
+4.5060000000000002	0.0537552245675751	0.0283855736696139	9.7919259724505849	-0.0771734007259089	-0.1328971859217028	0.0468387441011729	
+4.5069999999999997	0.0497792257090304	0.0248974957657579	9.7882167710670629	0.0930121393092031	-0.1373916480428513	0.2440807292291075	
+4.5080000000000000	0.0611422983055050	0.0210128612508999	9.7904295375658048	0.0232119932629271	-0.2121118151345052	0.2267297243792000	
+4.5090000000000003	0.0366988510532089	0.0101307079516962	9.8033861790026169	0.2928035809857353	-0.3821640798554590	0.3230005077441765	
+4.5099999999999998	0.0551262386206934	0.0114727337682473	9.7794859229088473	-0.0173083647851437	-0.1064179423743542	-0.1834887327416586	
+4.5110000000000001	0.0503270489804647	0.0166953509521658	9.7870073655329684	0.0583157845453099	0.1081126888273155	-0.0030862143909486	
+4.5119999999999996	0.0558831047646174	0.0157686883665629	9.7861007659090529	-0.2447895693662649	0.0075787240305709	-0.0547328414829797	
+4.5129999999999999	0.0586372447936128	0.0468561048386889	9.7956292998561043	0.3219556356341272	-0.0563650021978149	0.1039446535845158	
+4.5139999999999993	0.0475110507532124	0.0317299863297021	9.7848482432352810	-0.0207067155720076	-0.1076008955050618	0.1366859309082236	
+4.5149999999999997	0.0425142536419870	0.0331729782349706	9.7738467610934254	-0.3034678293047658	-0.1785623606723209	0.0917940269200767	
+4.5160000000000000	0.0692402303213775	0.0171915036880101	9.7754121350060856	0.1570527173949262	0.0619781595885202	0.2557870286719802	
+4.5169999999999995	0.0559684208527312	0.0168006338466369	9.7968886824077881	0.0285643226373614	-0.1830521399107591	0.0006471662884720	
+4.5179999999999998	0.0569273944741472	0.0198222955696824	9.7835003143769423	0.2848121847047488	0.1983971284435701	0.0734016457233462	
+4.5190000000000001	0.0540181893333582	0.0225561074818462	9.7661161785608694	0.0745743750277267	-0.0664165726759271	0.0614954332546026	
+4.5199999999999996	0.0479561850250012	0.0202724530685954	9.7823775235433477	-0.0315093490007684	0.0037658237814035	0.0347649130191204	
+4.5209999999999999	0.0750476345857323	0.0405211442438051	9.7921095174517436	0.0555983528855415	0.1323546878772145	-0.2268858463909177	
+4.5220000000000002	0.0608032756308541	0.0108616658174112	9.7753915454208578	0.0407649220907765	-0.0284738471385008	0.0140931088127869	
+4.5229999999999997	0.0417423892059980	0.0361304052206873	9.7959877278263257	0.0940967693027746	0.1083914159097912	0.3680179891900716	
+4.5240000000000000	0.0226509810987965	0.0267986911485683	9.7856084572525379	0.1494370488607169	-0.1364208741982287	0.0314652658924186	
+4.5250000000000004	0.0751917612738763	0.0002662099715962	9.7906697025215585	0.2931827940871106	-0.1572324412534201	0.1405300826451934	
+4.5259999999999998	0.0475719675467366	0.0291044258886728	9.7900438602792956	-0.1102046053403069	-0.1443892722723318	0.1882617214408647	
+4.5270000000000001	0.0589884304417820	0.0392804335410149	9.7837182434934409	-0.1372959827092591	0.0489178489913547	0.2176478758491452	
+4.5279999999999996	0.0432501883565825	0.0054656610375931	9.7664141901971053	0.0388625529931468	-0.0942918090186652	-0.2127993278141402	
+4.5289999999999999	0.0515698369279258	0.0386835281091434	9.7911827006623735	0.3964745695451854	0.1075681039221983	0.0034196785745579	
+4.5299999999999994	0.0597427243034189	0.0220947837119378	9.7826823348001071	-0.0469026301917689	-0.0553764914245260	0.1402164056315882	
+4.5309999999999997	0.0610373003152265	0.0251104214872230	9.7774663401148363	-0.0728236543675173	0.0532900915892882	0.2309148565386283	
+4.5320000000000000	0.0411182762630753	0.0193795014068199	9.7802956686581055	0.0456574234272840	0.1742565314788140	-0.0276349363200621	
+4.5329999999999995	0.0541604233110804	0.0271919940054292	9.7916127175371077	0.1443012529033045	0.0164317055862709	0.1704040099348771	
+4.5339999999999998	0.0363168163295042	0.0138126770709220	9.7685702961918057	0.0935878104232796	-0.1463510753022451	0.0772076848002106	
+4.5350000000000001	0.0454423714927909	0.0414573767415582	9.8072007531175469	0.0231017997197944	-0.2436696092532504	0.1059913789053996	
+4.5359999999999996	0.0597762601313614	0.0041032351959337	9.7938189647073788	0.1763007803122973	0.0959568184879638	0.0218906998708043	
+4.5369999999999999	0.0511715323346155	0.0175407191560249	9.7865685063505783	-0.0819983594189682	0.0169388700013480	0.3206251171715503	
+4.5380000000000003	0.0666548559385797	0.0246342725012256	9.7949880458151046	-0.1204713150074348	-0.2664361788130091	-0.1877598861304752	
+4.5389999999999997	0.0397626725629855	0.0170429855630472	9.7911282940026823	-0.1380505040877411	0.2744251125844597	0.2617073275113719	
+4.5400000000000000	0.0484403272509196	0.0223659148200867	9.8025096244883390	-0.0516119478282493	-0.2719711413379320	-0.1788057549771767	
+4.5410000000000004	0.0395181972974111	0.0272687262369054	9.7773226501598849	0.3585360037856613	-0.0064409890649702	0.0377052212045912	
+4.5419999999999998	0.0800720182027106	0.0350145314199208	9.7745605611613637	-0.1947260465985645	0.0179651008443316	0.2779040886955960	
+4.5430000000000001	0.0566406379751094	0.0135304720804014	9.7903264758870225	0.3007732501631530	-0.0995010983961892	0.0184874963662535	
+4.5439999999999996	0.0642391467986826	0.0280796648848884	9.7738161759564708	-0.1223355066602406	0.1152411375163682	-0.0424634990723316	
+4.5449999999999999	0.0478932267486794	0.0221408891189263	9.7731588334794068	-0.2161483197756217	0.0190157498354911	0.1751320180191654	
+4.5459999999999994	0.0264341105396296	0.0259420640474317	9.8073824392291513	0.0260532853188209	0.2323268312324871	-0.0375307825518574	
+4.5469999999999997	0.0693491020162070	0.0310357677550851	9.7722525879119768	0.0894240817432715	0.0694333550889985	0.0953333902102910	
+4.5480000000000000	0.0438056053101706	0.0483875718743737	9.7924882913541840	0.1405405717079488	-0.2228670563557976	-0.1830554448391401	
+4.5489999999999995	0.0366957887287783	0.0233809903579657	9.8118314944801543	0.2194222300194344	-0.0238231150659176	0.2678135028288096	
+4.5499999999999998	0.0532689824481028	0.0235756965399821	9.7997750015044041	0.1406507553725620	0.2952864302100189	0.0668659544194246	
+4.5510000000000002	0.0292651567046141	0.0095842320465604	9.7905917416176145	0.3411852125070992	-0.0012741447062321	-0.0095337123038730	
+4.5519999999999996	0.0654591660113070	0.0357600167546560	9.7901909071152478	-0.0505392714425822	0.0634410733293161	0.1125344152636347	
+4.5529999999999999	0.0554025567039691	0.0102582243361827	9.7708589746291015	0.3096893086466498	-0.0074387356865506	0.0509956767063158	
+4.5540000000000003	0.0470388510861476	0.0206733728117231	9.7937675940029525	0.2575453475053917	0.0505161020279103	0.2858817336856151	
+4.5549999999999997	0.0768073645009337	0.0163661840243164	9.7896599461820646	0.2948578425547511	-0.0999019915698492	0.0213881525821078	
+4.5560000000000000	0.0470892819237733	0.0152185263691674	9.7922560732959187	0.0443518727828663	0.0242139605593385	0.0569275473892899	
+4.5570000000000004	0.0482365257611768	0.0168463979909604	9.7669360886910130	0.4717697976204004	-0.2644116533361052	0.2285130961538966	
+4.5579999999999998	0.0493198989700075	0.0110804249784742	9.7956233590925237	-0.0740107665768525	0.0310959675707559	0.1046543949735944	
+4.5590000000000002	0.0709697389538741	0.0087129350157798	9.8166922794182021	-0.1522111738936144	-0.1587251094031662	-0.0388987203635494	
+4.5599999999999996	0.0558889635922844	0.0250278268128023	9.7842637039368601	0.1043922492320159	-0.1156810695406274	0.1986484273432916	
+4.5609999999999999	0.0691865941198874	0.0183076459604566	9.7814147913616871	0.1814832170883900	-0.1408251783333145	-0.0433876316553475	
+4.5619999999999994	0.0434216826683130	0.0160623418114125	9.7898801460955518	0.2401110726480367	-0.0391233314244556	-0.0070066773837880	
+4.5629999999999997	0.0481954442245531	0.0087455361118192	9.8083373717264273	-0.1964583443673649	-0.2376283619490204	0.1849268519808410	
+4.5640000000000001	0.0647707306002544	0.0280009204137386	9.7775224055311867	0.2042776075952037	-0.0482308324086836	0.1858140762619837	
+4.5649999999999995	0.0350778005138721	0.0281468555353072	9.8078940877224063	-0.1036757396664311	-0.0380155890960683	0.1649195963801894	
+4.5659999999999998	0.0552056827316273	0.0132558300773812	9.7784367925581890	0.4035250412228822	-0.1646859155603809	0.1107797517307811	
+4.5670000000000002	0.0595177558635253	0.0384278546469068	9.7629939525090599	0.0880232719987135	0.0635039620054380	-0.0409741417320240	
+4.5679999999999996	0.0807650700189564	0.0268942265244027	9.7644390543670809	0.0382458680250217	-0.1704454295885173	-0.0312534395686997	
+4.5690000000000000	0.0579025170836501	0.0168872744087947	9.7988560850120585	-0.0298776370301519	-0.0311132678427611	0.0167722861130681	
+4.5700000000000003	0.0555355598256919	0.0010821175489733	9.8162456382305034	0.3363061332364409	0.0441593124864129	0.3150167503758372	
+4.5709999999999997	0.0740848554317654	0.0455866555484172	9.7916034316390910	0.0574796547453492	-0.0340582985992255	0.2489953313020272	
+4.5720000000000001	0.0461484639914070	0.0216489134993051	9.7650742924503877	-0.1522498684733509	-0.0245767570747189	0.0641866644641572	
+4.5730000000000004	0.0676778707746517	0.0347286895169187	9.7850775675700170	0.0269068394354192	-0.0063902385108912	0.3296015237688631	
+4.5739999999999998	0.0638311111220204	0.0090314094667864	9.7895805352905558	-0.1212500008135721	-0.2292331386643734	-0.0439864729397925	
+4.5750000000000002	0.0465275218166182	0.0249520816368451	9.7810738393112135	0.2281350974301477	-0.1310034436121572	0.1600565695569598	
+4.5759999999999996	0.0577760480160608	0.0183479031594445	9.7824208853367214	0.0774923832492904	0.1832091744601040	0.0288513988419942	
+4.5770000000000000	0.0779498114962984	0.0358807027072000	9.7822220892371465	-0.0474079569855185	-0.1306694588151891	-0.3213205010896741	
+4.5779999999999994	0.0676043400507280	0.0126156400240725	9.7969936425266546	-0.0123692426765986	-0.0369835777937452	0.0645847715753597	
+4.5789999999999997	0.0614381090452430	0.0410029179375322	9.7901222046749883	0.1738262468321812	-0.0072182705565362	0.1193076957531205	
+4.5800000000000001	0.0618755249264670	0.0141955925479308	9.7828139626383717	0.0322643674788497	0.0533421199545293	0.2809994617155968	
+4.5809999999999995	0.0431334316629817	0.0176907949943455	9.7764274086121485	-0.1825304859984647	0.0771267966176036	0.0655592361227602	
+4.5819999999999999	0.0666437486546392	0.0172067311675950	9.7918379258234918	0.2410287267495704	-0.1089924739415535	-0.2094932651304829	
+4.5830000000000002	0.0511042378903128	0.0170054885089105	9.8051284666284868	0.0957383057340955	-0.2697298133083185	0.0455911445056133	
+4.5839999999999996	0.0349012642834725	0.0316747846124256	9.7789007060754329	-0.1379128113372651	-0.1626578810115103	0.1103946489631402	
+4.5850000000000000	0.0503415478202437	0.0251626720856273	9.7682241243016357	0.0389103046176690	0.0349316721157207	-0.1655050314679665	
+4.5860000000000003	0.0608292098506302	0.0113581437375784	9.7842872999666426	-0.1691276504005313	0.2440646524342283	-0.0816397017713366	
+4.5869999999999997	0.0576623880441307	0.0091047082152194	9.7933392893718327	0.2847725896574431	-0.2159239801005557	0.0331325251413659	
+4.5880000000000001	0.0628125560901645	0.0364950696988635	9.7770233872181773	0.2034115542269586	0.0370684321834168	0.0578801270097137	
+4.5890000000000004	0.0583742354544998	0.0341938728716268	9.7756869577425043	0.1563601928543722	-0.0518400557354797	-0.0473127844303225	
+4.5899999999999999	0.0673254870444648	0.0307466574544555	9.7834726007637585	0.0342707194191745	0.0509584128351851	0.0499142133480461	
+4.5910000000000002	0.0555591451784983	0.0057142869447534	9.7865198873354107	-0.0461074723222129	-0.3845741979321842	0.0787377789958794	
+4.5919999999999996	0.0503346368768995	0.0217027350787757	9.7825280793260383	0.0454187860190256	-0.2844114638057210	0.0355560805453482	
+4.5930000000000000	0.0619226500052716	0.0395013054720298	9.7824866817467750	0.1242534253672146	-0.1695866825132296	-0.0239662637524903	
+4.5939999999999994	0.0550908189341681	0.0281510313510486	9.8130592323191603	0.0088524655326842	-0.1171307456936343	0.2001385949519822	
+4.5949999999999998	0.0412370124963094	0.0419123658568198	9.7874207884524189	-0.1327312733451208	0.1252950693756822	0.1430257447437809	
+4.5960000000000001	0.0622918327094928	0.0150753919378662	9.7762349082143061	0.0404417619162467	-0.1055306060257902	-0.0115110290497785	
+4.5969999999999995	0.0366369072308972	0.0027957473959756	9.7676312265076923	0.2783928748174269	0.2171592303214242	0.2379873759663826	
+4.5979999999999999	0.0690220257280064	0.0300634085204332	9.7782035763993669	-0.0598354596394300	0.2315180602728855	0.3089187623470124	
+4.5990000000000002	0.0466128497844000	0.0376578202578495	9.7873968581490143	0.1034691265437701	-0.1818441985182817	-0.0522418890786702	
+4.5999999999999996	0.0441009256206206	0.0461920740697648	9.7788983998522028	0.0363962788462886	-0.0283822948457469	0.1225557396598670	
+4.6010000000000000	0.0469860609439775	0.0363385517268240	9.7782667487839188	0.0146562056909011	-0.0023808145433717	0.4642929022575193	
+4.6020000000000003	0.0497762354356242	0.0370981431870386	9.7845767432731012	-0.1569310543086730	0.1235452654590742	-0.0946029279322533	
+4.6029999999999998	0.0475309151593360	0.0197560458517564	9.8011551485028754	0.0238986140498101	0.0772536759379389	0.0322383846489784	
+4.6040000000000001	0.0525002464459330	0.0539571896779696	9.7889109351599863	0.2135756136690511	-0.0706936285339877	0.0106041871914295	
+4.6049999999999995	0.0394620552958267	0.0323642779475443	9.7907676858033739	-0.0799289970545323	-0.0926506504713244	0.2687246791708823	
+4.6059999999999999	0.0774746603742251	0.0200327188157561	9.7889556845003742	0.4451260927529739	0.0041888374457861	0.1360658714792042	
+4.6069999999999993	0.0505733672540819	0.0266947100552779	9.8031628313269472	0.0867310318802722	0.0003444579815507	0.1865932757909275	
+4.6079999999999997	0.0503381515172218	0.0281910038362438	9.7706647298978648	-0.0131407478457174	0.0506823357798275	-0.1300207622233489	
+4.6090000000000000	0.0767875115504235	0.0433287201618371	9.8134344209186857	-0.1057312532466101	-0.0116120181502883	0.0976580534521312	
+4.6099999999999994	0.0585847748546106	0.0056269558077906	9.7920234883283452	0.0941978163990033	-0.1882541598121148	0.4358415019421955	
+4.6109999999999998	0.0380854736837787	0.0169292434276776	9.7791882672934456	0.2409532005088131	-0.2507075614764845	0.1185516413022117	
+4.6120000000000001	0.0342403436944108	0.0240800096227053	9.8086285666530948	0.0334191400941121	-0.2894235947982656	-0.1013373620825268	
+4.6129999999999995	0.0712500457763850	0.0137765020177101	9.7836188081836450	-0.1415636903731624	-0.1300610553166346	0.0055487266352916	
+4.6139999999999999	0.0588379516736298	0.0108312138631593	9.7828071488112816	-0.1045592678205792	-0.0786594605491476	0.0451215053587021	
+4.6150000000000002	0.0577005069588528	0.0153872421711973	9.7834961040292168	0.1106146289587030	-0.0890454277588318	0.0736652664101276	
+4.6159999999999997	0.0483295871322594	0.0211849755284160	9.7841793674047821	-0.0236473781948582	-0.1843734500449611	0.1380425982936151	
+4.6170000000000000	0.0594272374477427	0.0307739300238682	9.7882693280351791	-0.0013610945311348	0.0267384928180201	-0.0216315782470180	
+4.6180000000000003	0.0691984104840630	-0.0020905522743108	9.7996400521384839	-0.1952981550747306	-0.1009271340483810	0.0481338478754294	
+4.6189999999999998	0.0777199970794354	0.0054011240635954	9.8040886573088670	-0.0242815435384941	0.1160290893358090	0.2428591089277520	
+4.6200000000000001	0.0578749621897278	0.0206948187621633	9.7732274446472189	-0.1771957387815637	0.0354192315430192	0.0779349049541047	
+4.6209999999999996	0.0666174774263995	0.0163747512032121	9.7819240019689779	-0.0202378746437872	-0.1770283165875133	0.2359866318377168	
+4.6219999999999999	0.0377432428734491	0.0253829711374203	9.7809539793900626	0.0943583271680782	-0.0586666604506261	0.1158121672928106	
+4.6229999999999993	0.0483614986915921	0.0021119204937758	9.7894443955498485	-0.0483509555967471	-0.0830293398591822	0.0875856444157919	
+4.6239999999999997	0.0938032157360802	0.0323180044868866	9.7679633457345165	-0.0488293851945581	-0.1950801630173987	0.1253553250440300	
+4.6250000000000000	0.0500563709341787	0.0168259133669345	9.7878188240359467	0.1579467223946341	-0.1765009412885866	-0.0055682272485108	
+4.6259999999999994	0.0547903562407354	0.0416454126355795	9.8000566547318861	-0.1806272457704231	0.0909755361991002	0.1791070267839408	
+4.6269999999999998	0.0348688196324930	0.0270168724370508	9.8251287936692293	0.2477056261240417	-0.1720666237437576	0.2108903654158342	
+4.6280000000000001	0.0642676610167702	0.0378321351142901	9.7819964581323617	0.1844003821086919	0.0744943040937722	0.2704382418129461	
+4.6289999999999996	0.0610397552608999	0.0213725900892596	9.7894439863863632	0.0066821087812886	-0.2277532723624456	0.0481404724195527	
+4.6299999999999999	0.0523901465361534	0.0293709947713769	9.7866657968065649	0.2509902746589316	0.0768062986556756	0.0196479452963034	
+4.6310000000000002	0.0691989804691543	0.0163939407144952	9.7855804959988983	0.0059474316894394	-0.0728389256176052	-0.0187116127179513	
+4.6319999999999997	0.0647517873676439	0.0277180669315866	9.7965828347934476	0.1221841709799083	0.2582718154757381	0.0586362813191306	
+4.6330000000000000	0.0557320381592892	0.0233482476158439	9.7891499422174810	0.0964321949648500	-0.0180903868003315	-0.0821120980350837	
+4.6340000000000003	0.0428808763503736	0.0256935169728591	9.7859085707199878	-0.1152900820418220	-0.0079228897671285	0.0838746781605551	
+4.6349999999999998	0.0615007126506043	0.0122822102701365	9.7843841135844585	0.1327533304970090	-0.1805983069381968	0.1514862378278951	
+4.6360000000000001	0.0491595923065488	0.0252085225036505	9.7784444405013247	-0.2348035491879178	-0.0513747125914808	-0.1074209866042769	
+4.6369999999999996	0.0520563626200461	0.0414964128512136	9.7857722332081121	0.2029614251104765	-0.3372561261558845	0.2373209969519176	
+4.6379999999999999	0.0496368029391293	0.0044133526772973	9.7775264119633345	0.2109992929730211	0.0385262543878672	0.2894643701265599	
+4.6389999999999993	0.0605695220892314	0.0315289952030286	9.7628710977015185	-0.0551523720660314	-0.0629585106915788	0.2461963065594074	
+4.6399999999999997	0.0495321901256192	0.0037722627628008	9.7774887859615909	0.0778944316455352	-0.0687083862879981	0.0689158230913481	
+4.6410000000000000	0.0446108789650980	0.0492934905117438	9.7742152128265989	0.0871726409309605	-0.1404074825538241	0.2020021112504539	
+4.6419999999999995	0.0463066417417041	0.0259126203047821	9.7755299619924081	0.1560305679780395	0.1108631284213797	0.1319670071736235	
+4.6429999999999998	0.0529009274534045	0.0299076563248946	9.7942562964327102	-0.0899188484167220	-0.1552603040414411	0.1923536656604468	
+4.6440000000000001	0.0469047677225206	0.0145161121063061	9.8039151381091152	0.1295353875164262	0.1053258081660896	0.0312274715124411	
+4.6449999999999996	0.0595280394806156	0.0108728038354381	9.7868095903244914	0.0637401901326921	-0.1292139685025182	0.3303045575155815	
+4.6459999999999999	0.0453372947514247	0.0321363819522936	9.7673346001348769	0.0623081529431211	-0.0919223417433399	0.2719371943319523	
+4.6470000000000002	0.0576046401498358	0.0184745166937808	9.8199159417854212	0.0846926429026717	0.1149446899674642	0.0814046734344018	
+4.6479999999999997	0.0452057304329862	0.0170578946550763	9.7788297595468361	0.1292248409270477	-0.1817238945367727	0.0393044235441676	
+4.6490000000000000	0.0476881776646061	0.0239966238170438	9.7927087523538194	-0.0090853106799655	-0.1766863208449740	0.1106903655451151	
+4.6500000000000004	0.0493641501695994	0.0053998755645205	9.7853186779589016	0.0297077649845368	-0.1595709694455097	-0.1490574128347010	
+4.6509999999999998	0.0529884192120388	-0.0075112637376741	9.7873063822966415	-0.2972567873112584	0.0328297919768730	-0.0673785034425451	
+4.6520000000000001	0.0373096399065948	0.0204160299690394	9.7980355801499392	-0.1300856574842039	-0.2295977097434493	0.1552965241386069	
+4.6529999999999996	0.0505415055855464	0.0313171034147730	9.7984522402559406	-0.0450017868145570	0.2788370031575830	0.1860120668061217	
+4.6539999999999999	0.0422066214006469	0.0070523739111898	9.7870967886588645	0.0486737893450082	0.0780910848850719	0.1584685581995703	
+4.6549999999999994	0.0701216880459539	-0.0040018818054374	9.7984374158918346	-0.0521849581553661	-0.4223553606442726	0.0204776171382494	
+4.6559999999999997	0.0601296289509584	0.0370347615986659	9.8070581707002837	0.0726419263565490	0.3039206637276595	0.0629516988249841	
+4.6570000000000000	0.0545431172945147	0.0132421660360592	9.7811043678014222	0.2223544812562356	0.0416006782220905	0.1952224075386603	
+4.6579999999999995	0.0585688409354638	0.0290219957531857	9.7774887543263471	-0.1273388560718206	-0.1467596737869099	-0.0032484548066842	
+4.6589999999999998	0.0684999941233800	0.0068920464156608	9.7883986344888516	-0.0197572932696389	-0.1191236664330236	0.1074595843335590	
+4.6600000000000001	0.0371638982905914	-0.0116430821292254	9.7809626260788711	-0.0223387931478033	-0.0845697071451213	0.0207838792192069	
+4.6609999999999996	0.0691181563967699	0.0289553298884133	9.7771430766491747	0.1675464739280896	0.0572989664162450	0.1991445095775916	
+4.6619999999999999	0.0880143732527208	0.0156516651315268	9.7864615827697605	-0.0691388048130823	0.0960131401201961	0.2580170595274715	
+4.6630000000000003	0.0275094176363530	0.0336270250183436	9.7701635421301365	0.0555870443918992	0.0929552802259110	0.1144755314799900	
+4.6639999999999997	0.0482987521369294	0.0287066625293411	9.7826168005265011	0.1091693840793535	-0.0422041985115869	0.0199773550839970	
+4.6650000000000000	0.0612706185505532	0.0336491789221058	9.7616237838936630	0.1592388440413849	-0.1264388751719808	0.0154823158584167	
+4.6660000000000004	0.0545576576996486	0.0265653968711577	9.7843980128505947	0.1289759105487954	0.1059015604342551	-0.0721718592308718	
+4.6669999999999998	0.0531597287043515	0.0023614613092349	9.7742743967421912	0.1057690143465320	0.0239542712337853	0.1298221711762232	
+4.6680000000000001	0.0631880021423225	0.0141472298546253	9.7873504659797526	0.1682577634270805	-0.0609838275284238	0.0046159667103362	
+4.6689999999999996	0.0710264004343654	0.0382468298421903	9.7792719582703018	0.0764873000478422	0.0492509283769953	0.2281490629127622	
+4.6699999999999999	0.0624158749318318	0.0331009100992789	9.7682907420251208	0.0058866612465078	-0.3618831526119495	0.0452777696201295	
+4.6709999999999994	0.0576637295102800	0.0418120466803537	9.8038897165413577	0.3810988511177839	0.0568840895990961	-0.1288258388040234	
+4.6719999999999997	0.0620372317345709	0.0061606142758568	9.7773006449849849	0.1587322849994971	-0.2076967817965550	0.0999424732094472	
+4.6730000000000000	0.0794070421824956	0.0171012687046976	9.7823252220842534	0.2656454464052252	0.0495034503445170	0.0753668831434220	
+4.6739999999999995	0.0629650716477617	0.0240384656632589	9.7810410958536895	-0.2480973786904286	-0.1033188697539295	0.0642084450478718	
+4.6749999999999998	0.0587680431103795	0.0459050666965506	9.7883762243137884	0.2161720360618342	0.2312674876061654	0.2232330797861033	
+4.6760000000000002	0.0666595974018694	0.0252275390637699	9.7822532591906750	0.0420963336080513	-0.1342152605508799	0.1819877226189458	
+4.6769999999999996	0.0638953245616527	0.0111880682628792	9.7955763053473550	0.1681773691335323	0.0476177309965913	0.2244817546133742	
+4.6779999999999999	0.0524402141649588	0.0195685504779928	9.7879158958029961	0.0716765299704223	-0.3568486879955514	-0.0733257618462830	
+4.6790000000000003	0.0704901733845160	0.0024867259296989	9.7912546233887827	0.0700728433604931	0.0069251127121685	-0.1484757976808846	
+4.6799999999999997	0.0441733307320502	0.0314779139054003	9.7900963664177212	0.1406399215476936	0.0620938211497140	0.3041169495101197	
+4.6810000000000000	0.0532758275601684	0.0335507844391117	9.7998187942951596	0.1371142437054880	-0.0436167469707361	0.0892149324647846	
+4.6820000000000004	0.0408002076747169	-0.0071648122806481	9.7844892114413113	0.2484380909192205	-0.1798427790862425	-0.2227826891906933	
+4.6829999999999998	0.0640308224087340	0.0465412568855648	9.7886815478347451	0.0520262880155047	-0.3582514074551586	-0.0870800510702087	
+4.6840000000000002	0.0508056440233988	0.0183103951038206	9.7933034173310904	-0.3045911747788455	-0.1354966394047978	0.3919454716234262	
+4.6849999999999996	0.0566990729566195	0.0125652322991044	9.7715661422078330	0.2436199827799775	0.0612993551589292	0.1578002796839479	
+4.6859999999999999	0.0710303843724850	0.0326440444632910	9.7897622587036519	0.0694518403397146	0.2427355292128785	0.2167808096246043	
+4.6869999999999994	0.0417240258168495	0.0106055945496121	9.7785266875249697	-0.3065865895347616	0.0272052975558403	-0.0723139398472349	
+4.6879999999999997	0.0458483357317274	0.0087463727940757	9.7799699660649697	-0.2700623362333338	-0.0134883973341827	0.0057382151173737	
+4.6890000000000001	0.0516189846285489	0.0101745053805941	9.7782509608303432	-0.0751657834849022	-0.2611724974075726	-0.0468364551648014	
+4.6899999999999995	0.0545953222542360	0.0140684362667916	9.8005314003269586	-0.1138672179980231	-0.2100717502891312	-0.0896162627227145	
+4.6909999999999998	0.0338517968547803	0.0371435487977795	9.7803386499487974	-0.0578490524981291	-0.0766986873395576	0.0525592350268747	
+4.6920000000000002	0.0567518305038264	0.0194063775710151	9.7855769887285327	0.2243882637216057	0.0759913620973838	-0.1707039366515084	
+4.6929999999999996	0.0873807741437874	0.0355365634496562	9.7747856914139639	0.1300822200445428	0.0950590863576664	-0.0970884213354683	
+4.6940000000000000	0.0470147749979858	0.0264559748607014	9.7700705481764007	-0.0909223975878033	0.1939635813781443	-0.0402451884307711	
+4.6950000000000003	0.0531986331521998	0.0277363523847373	9.8055528660531337	0.1475993985803650	-0.1598982047631291	0.1028729249986771	
+4.6959999999999997	0.0552019729779557	0.0347402425358740	9.8050847549042448	-0.1548942258078291	-0.1979056062328435	-0.0460452173863461	
+4.6970000000000001	0.0502135699595102	0.0186467211211854	9.7905288015743750	0.2475805735487731	-0.1671899063704293	0.2221802360606142	
+4.6980000000000004	0.0638189836935674	0.0306090032182619	9.7842343156383134	0.4899469714603796	-0.0286180388377532	0.0476787690201636	
+4.6989999999999998	0.0602370496049944	0.0145139093994247	9.7789209076706705	-0.1028522107598982	-0.3697564431957379	-0.0250726991731944	
+4.7000000000000002	0.0300756191730493	0.0232737935741279	9.8030104562949063	0.0911138127771333	-0.2491817209049103	-0.1357828635435444	
+4.7009999999999996	0.0561024178589212	0.0240215011168013	9.7823099375610774	0.2686762799662049	-0.2230083202075106	0.0440846178342129	
+4.7020000000000000	0.0649339427445736	0.0286548629374055	9.7434991807294011	0.1257852129271902	-0.0819751639095082	0.1239154615133692	
+4.7029999999999994	0.0635284497905224	0.0343310304132951	9.7900457899771123	0.0824236660764195	-0.0658199705300064	0.0255395113980477	
+4.7039999999999997	0.0433064700375782	0.0116934618478617	9.7647975147088744	-0.0586513240247817	-0.0551654183487362	-0.0560548839963011	
+4.7050000000000001	0.0364713148677975	0.0318108965987502	9.7978735259507221	-0.0552671374067023	0.1437293095289514	-0.0323378861356701	
+4.7059999999999995	0.0743310544764535	0.0300573222625401	9.7673739423056603	-0.1084835968614458	0.1771843931048853	0.0709954493279685	
+4.7069999999999999	0.0405115883059017	0.0412615548288756	9.7780895171774098	0.1616638532790471	0.2211192303986664	0.1296934456037155	
+4.7080000000000002	0.0423486299517499	0.0214646021164815	9.8027854430232004	-0.0044751109280502	-0.2574121162898570	-0.0131958452692992	
+4.7089999999999996	0.0628925880425288	0.0275773482900370	9.8065708552415227	-0.2042352908010744	-0.3118713707920208	0.0360598480363004	
+4.7100000000000000	0.0379694976011796	0.0333149279393496	9.7830849977792163	0.2518758134843883	0.2657127710699302	0.2696349618688010	
+4.7110000000000003	0.0382264699417532	0.0071706913565298	9.8014033549951414	-0.1086859657237849	-0.2030285371875442	-0.0284314235128324	
+4.7119999999999997	0.0535921536083552	0.0169185452939826	9.7947293727078577	0.2345129394223521	-0.1027849719358784	0.0797445339642766	
+4.7130000000000001	0.0302859370980037	0.0450211013547232	9.7863200095185743	-0.0674279287011775	-0.0215875775763283	0.0731944416385495	
+4.7140000000000004	0.0450196299909438	0.0141622995183393	9.7940828908034590	-0.1541799406352362	0.3702184819488073	0.1108623046449352	
+4.7149999999999999	0.0564835185880505	0.0350491892576625	9.7964282396204272	0.1512438177678114	-0.1780992544337082	-0.0756566765192986	
+4.7160000000000002	0.0702716757478482	0.0332105744981874	9.7902235875979837	0.0377563700625708	-0.1072448555327279	0.2028153075456924	
+4.7169999999999996	0.0434838081913422	0.0286155542205309	9.7854766588307402	-0.1647681505495686	-0.2354988320230654	0.1790758701952386	
+4.7180000000000000	0.0637044486068106	0.0298667025066427	9.7950230188177230	-0.0409082932682064	-0.0934129930097659	0.1450361906423812	
+4.7189999999999994	0.0581346714114347	0.0273815266062277	9.7884247948290284	-0.1011400007101406	-0.1402138097334936	0.1256805042568286	
+4.7199999999999998	0.0545929582976424	0.0304385845847330	9.8006409695358325	0.0074111850730543	-0.1454008380737481	0.2498795937826140	
+4.7210000000000001	0.0480844927649662	0.0320334029660283	9.7837497901444195	0.3130269833808166	-0.1396802563824611	-0.0658906474739125	
+4.7219999999999995	0.0352209502728551	0.0075524433239956	9.7873047676200731	-0.0635002314413564	0.1413359988164824	0.1630865777684105	
+4.7229999999999999	0.0465397489070943	0.0435185748986745	9.7927380149191876	-0.0783313841198081	0.1833998156023096	-0.1526023113737672	
+4.7240000000000002	0.0575628278026271	0.0272848704785799	9.7922641928780401	-0.0356634748296746	0.0348763016407035	-0.0004579869923266	
+4.7249999999999996	0.0659713890155383	0.0503434222060542	9.7954019748881471	-0.1586519808395447	0.0609675176234014	0.0941281706322197	
+4.7260000000000000	0.0327419281470653	0.0161054254905695	9.7943409288855605	-0.0958985070779484	-0.1458192544640831	0.2018110101652077	
+4.7270000000000003	0.0336441072462841	0.0092673771238274	9.7872744309397408	-0.0428781587782512	-0.0057508838754622	-0.0048645867398687	
+4.7279999999999998	0.0611647736962877	0.0270261226114017	9.7928979614663980	-0.0476720031616851	-0.0356416664130789	0.1255745099551596	
+4.7290000000000001	0.0831852693844203	0.0299499095864347	9.7780715602381427	-0.1012020982501610	-0.1325488323983848	0.0921271205582906	
+4.7299999999999995	0.0258577699567666	0.0123597707245323	9.7903975092544364	0.0881271657832910	-0.2195340705810660	-0.1026060660259235	
+4.7309999999999999	0.0447704202787158	0.0258671806914989	9.7853165691171782	0.1130930803465604	0.0376753619825974	-0.0673561358438259	
+4.7319999999999993	0.0580805664997442	0.0175593310920690	9.7864225919421806	-0.0089166359665676	-0.2197627149226646	0.1754219090525377	
+4.7329999999999997	0.0476076026129047	0.0229226536458326	9.8114483730032784	0.0371098623146331	-0.0660715989260782	-0.1617766616241736	
+4.7340000000000000	0.0511060212496314	0.0303704921068207	9.7931046941958773	-0.0256301721983044	-0.2275337521168310	0.0148831828991335	
+4.7349999999999994	0.0695866027124470	0.0299462967371051	9.7776191860979882	0.1194441826254285	0.1196407474337097	0.1703432956735327	
+4.7359999999999998	0.0536497877605601	0.0296630546337299	9.7706401685868389	0.0589954601322409	-0.0021125200432553	0.0099455018928036	
+4.7370000000000001	0.0703542700294884	0.0195145434449075	9.8086932303179353	-0.0841077917703137	-0.1221218177112172	0.1247065053215580	
+4.7379999999999995	0.0605669713500800	0.0178883780991184	9.7957874910496390	-0.0710923805796671	0.1835968223832228	0.1564868576327181	
+4.7389999999999999	0.0618011895787000	0.0252846313192963	9.8147972610498364	0.1270108596749185	-0.0446253908089885	0.1543455927579674	
+4.7400000000000002	0.0764531368391589	0.0167841992788023	9.7873428590948226	0.2763440558409275	-0.1344832728202533	0.1950500808144886	
+4.7409999999999997	0.0421888411408051	0.0375258981926065	9.7766220572044435	-0.0978166875640480	0.2423655792540138	0.1707401869357873	
+4.7420000000000000	0.0659401760114021	0.0077831041746771	9.7917296826783318	-0.0462908300386754	-0.0150261829414733	-0.0643941990221949	
+4.7430000000000003	0.0598889863424999	0.0123628303147950	9.7848608478092629	0.0806338500807745	0.0562400634397059	0.0348024566555942	
+4.7439999999999998	0.0469068670073584	0.0314750603542507	9.7964251187856810	0.2072021622975339	-0.0566681081630877	0.0881097495726203	
+4.7450000000000001	0.0651879211521233	0.0335686553459413	9.7941068937158402	0.2225530382479142	0.2430934068463695	-0.0363999776231143	
+4.7459999999999996	0.0504592510527763	0.0354891016254580	9.7830158524396555	-0.0947922165487425	-0.1029819225281961	0.2909578596345508	
+4.7469999999999999	0.0654234299877271	0.0158253788236038	9.7740342908340292	-0.0116148905915222	0.0301943422731686	0.0727380259013838	
+4.7479999999999993	0.0606546280348232	-0.0047331808715710	9.7766085937331848	-0.1853998207500593	-0.2041608443272601	0.2996180511139965	
+4.7489999999999997	0.0554862227818537	0.0138755832820624	9.7866736757089789	0.3325290352390943	0.2245180447029560	0.1775309356568935	
+4.7500000000000000	0.0597594201907171	0.0191205404746054	9.7566450886497673	0.0749404624045490	-0.1805013139398394	0.0805978018972139	
+4.7509999999999994	0.0366622491752697	0.0107987355229442	9.7768935967065058	0.3107071132089978	-0.1824268663536857	0.2021736940106784	
+4.7519999999999998	0.0586564251226219	0.0116979939950994	9.7825868200762436	0.1052567901600699	-0.0933649030878859	-0.1176194795302416	
+4.7530000000000001	0.0550399320402679	-0.0036629382562814	9.7892698896679704	0.0487192845269681	-0.1638298291452053	0.3281706608914828	
+4.7539999999999996	0.0319668263673277	0.0177236978828271	9.7678843240654931	0.4092975187048249	-0.0485713202806565	0.0661609868716880	
+4.7549999999999999	0.0687997200851619	0.0191298082514892	9.7859905090082293	0.1195192944848323	-0.1692241532979617	0.1179924242483211	
+4.7560000000000002	0.0623244572244412	0.0179110480854742	9.7973805744658495	0.1218385300495397	-0.2925278053482438	0.1057194617146815	
+4.7569999999999997	0.0490653204394887	0.0167140857660073	9.7883692948199617	0.1666143120460450	-0.0179711110457012	-0.1125667432488437	
+4.7580000000000000	0.0628512850499550	0.0283237387978318	9.7953976563970357	0.0755989717962394	-0.1525270166597132	0.0376939442094140	
+4.7590000000000003	0.0664818009676386	0.0235940889298062	9.7943548204754798	0.0803652567819479	-0.0815878056499244	0.0608562893671598	
+4.7599999999999998	0.0311387505136666	0.0301568121073707	9.7800057406495569	0.0774933492404936	0.0587716707918873	0.3130149350936484	
+4.7610000000000001	0.0557016895294591	0.0202485029846633	9.7761516569286293	0.1120148804070463	-0.2155527434809481	0.2928848779862707	
+4.7619999999999996	0.0720404114455885	0.0169217943146153	9.8015788562924975	0.1209794306238063	-0.0788871643452031	0.1488557182836565	
+4.7629999999999999	0.0487634381921661	0.0121561941564906	9.7921555268689016	0.3484216132005954	-0.0982609113043509	-0.2847739882900439	
+4.7639999999999993	0.0515576837442308	0.0051508803554815	9.7842607018059624	0.1250307424769117	-0.2527822159803637	0.0068830336613355	
+4.7649999999999997	0.0750321296071569	0.0289352834497665	9.7827508197344493	-0.0168235930849241	0.0800716290834036	-0.1428839589486607	
+4.7660000000000000	0.0607143242716672	0.0082130790385761	9.7632610768339685	-0.0438156130673584	-0.0126013671190918	0.1295713784008413	
+4.7669999999999995	0.0321560791851230	0.0320994115031156	9.7807407344236932	0.1895386425275979	0.3087085455464241	0.1935227244509044	
+4.7679999999999998	0.0597632882132555	0.0145554707468311	9.7847634719638332	0.0954559413373344	-0.1691858050588410	0.3052891460993177	
+4.7690000000000001	0.0694337206144466	0.0541681656655720	9.7634265340966433	0.0753089827984546	0.1304795978587397	0.0155418276704108	
+4.7699999999999996	0.0449505180900352	0.0172950281472330	9.7794082298702740	0.0833123354359693	0.1893997144999831	0.4319396691611262	
+4.7709999999999999	0.0760678934922341	0.0364486990424125	9.7796965881165594	-0.1026531834811037	0.0933281316308606	0.3936254831146400	
+4.7720000000000002	0.0542295872200357	0.0297119151577658	9.7835137935983791	0.0038679254081971	0.1248889549276427	-0.0241000943359457	
+4.7729999999999997	0.0510287687507343	0.0150340348775520	9.8065690023785095	0.0937893430332368	-0.2455463814680763	0.1599728289257591	
+4.7740000000000000	0.0533225897791503	0.0307979328699631	9.8024081843446051	-0.1133325694977924	0.1761990236015807	0.0128659559232188	
+4.7750000000000004	0.0654418328864374	0.0278401754292160	9.7736619140547560	-0.0554594314641995	-0.3189745009625056	0.1294331684143263	
+4.7759999999999998	0.0631508273478811	0.0272193936393573	9.7913475589948291	0.0476564708001054	0.1643305845144939	0.1381794110759414	
+4.7770000000000001	0.0362693390757040	0.0375084831740068	9.7951249885345604	0.0849230561697944	-0.0799933362261463	0.1221526982801770	
+4.7779999999999996	0.0663139226800891	0.0165516628302605	9.7845065407439868	-0.2400380174343978	0.0428853142343905	0.1886889594120228	
+4.7789999999999999	0.0630093155231421	0.0200117206866000	9.7955690261868806	0.2189233550568395	-0.2075549478447389	0.4049757369484169	
+4.7799999999999994	0.0607130933047786	0.0388921346517126	9.7888601572772433	0.0962918403446767	0.1021587354746907	0.0742612656420513	
+4.7809999999999997	0.0661730177341272	0.0304169881558888	9.7734574615313274	-0.1241166176682467	-0.1928150402960507	-0.0345013144480710	
+4.7820000000000000	0.0594851749342392	0.0389844556804604	9.7672608298638064	0.1618253897073917	-0.0891535106132436	0.1689532082914906	
+4.7829999999999995	0.0661353062698529	0.0587771836170664	9.7750253213246712	0.0302687558803723	-0.1028232668801485	0.2259023123938557	
+4.7839999999999998	0.0597521817977791	0.0288262969385344	9.7681015016539074	0.3109966981502222	0.0184134598680672	0.3507246612113998	
+4.7850000000000001	0.0628039462199907	0.0200723713436320	9.8087195599143620	-0.1913177524352082	-0.0642151464362257	0.2448137447922430	
+4.7859999999999996	0.0537154578913888	0.0149095816292195	9.7681066288774208	0.1056080721024475	0.1644452436686643	-0.0638457409446525	
+4.7869999999999999	0.0677760566613826	0.0316258582123368	9.7952096422419874	0.0856625481649547	-0.0562633161343183	0.1349733542207988	
+4.7880000000000003	0.0446756582579777	0.0311954831269446	9.8035034833236541	0.0380395996985915	0.0958732323063506	0.0962319235891182	
+4.7889999999999997	0.0591142133875860	0.0033228074329833	9.7832881953155848	-0.0976132535667141	0.0538733752937746	0.0925711690074820	
+4.7900000000000000	0.0640356509642124	0.0181422002270328	9.7840649688094530	-0.0403096568537986	-0.0175626219589307	0.0817577050719981	
+4.7910000000000004	0.0602983505647796	0.0383210358444514	9.8138557905304733	0.0833619452774403	-0.1513484215439752	0.0540753404520259	
+4.7919999999999998	0.0528064968331458	0.0134899870143350	9.7862428167172748	0.1148168652147944	0.0045952135747654	-0.0047691975035687	
+4.7930000000000001	0.0475141764883226	0.0247422515664653	9.7975490021188154	0.1515158927639382	0.3414398862021593	0.2552123541558073	
+4.7939999999999996	0.0426125453468193	0.0097364914204699	9.7839322024029158	-0.3527810695228040	0.0379671754016274	0.0380181606135587	
+4.7949999999999999	0.0620689873101209	0.0056958659061381	9.7891969205412064	0.5536680912899430	0.1377992225953160	0.0991385701578353	
+4.7959999999999994	0.0649682938850228	0.0119380132075161	9.7884711297133169	0.0053085692006229	0.1063983010592094	-0.0177240340578401	
+4.7969999999999997	0.0500514723012727	0.0108133927409152	9.7838578714595545	0.1316305944804144	0.3988639117388920	0.0932961044960248	
+4.7980000000000000	0.0644020119561639	0.0307841269548783	9.7803285697079279	0.2133738535398540	-0.2911504016407080	-0.0008689512058332	
+4.7989999999999995	0.0456400563222564	0.0269011470871114	9.7826066068408952	0.1623759121077250	-0.0208497626167559	-0.1333803060969372	
+4.7999999999999998	0.0601963410544195	0.0128932189916039	9.8043626986688803	0.1549617167243058	-0.1334382310323025	0.1278208788524763	
+4.8010000000000002	0.0645510427025683	0.0325837807403539	9.7830059710581949	-0.0486987533415035	-0.0804426601114660	-0.0059633151450516	
+4.8019999999999996	0.0432078300326044	0.0140872459012502	9.7872355255441619	0.1063263310126050	-0.2646510387075608	0.0697858692532238	
+4.8029999999999999	0.0609621412784363	0.0110424679198555	9.8086457006698851	-0.1741247263482225	0.0231503818497990	0.2913772836824246	
+4.8040000000000003	0.0550007973977442	-0.0018134226896190	9.7834487994783039	0.2186776711082309	-0.2071208713278908	0.2152410809254203	
+4.8049999999999997	0.0592283428425030	0.0104500136270922	9.7928554479777379	-0.1126212512879761	0.3016976099293511	-0.0583691344718530	
+4.8060000000000000	0.0457891836829923	0.0228389050463565	9.7972949650306802	-0.2220984539251373	-0.4193408727661772	-0.0284956724771161	
+4.8070000000000004	0.0611933503200568	0.0116302368376529	9.7935171764679616	0.3303547262948495	-0.1768222996507091	0.1121827056371025	
+4.8079999999999998	0.0478844762415916	0.0258127164089629	9.7917318491926419	0.1612358010486715	0.1582390298318337	0.0704453791224736	
+4.8090000000000002	0.0632043368731429	0.0244424040670178	9.7856337731534637	-0.2623190974535424	-0.1027900327682025	0.3095576715797275	
+4.8099999999999996	0.0548759349164324	0.0310246860614296	9.7815650505808787	0.0822078305084358	-0.0593899257838330	0.0194170827689677	
+4.8109999999999999	0.0415989160980958	0.0151846350419985	9.7753625569832217	0.1308222658140004	-0.2194698479695544	0.1044685419861433	
+4.8119999999999994	0.0505426835932809	0.0244601381796104	9.7693674515730571	0.0243641176027878	-0.1557639142824392	0.0350165745854910	
+4.8129999999999997	0.0433116105928556	0.0205598358855888	9.7951862063430291	-0.1311722509573501	-0.2151977994555580	0.0245145402196391	
+4.8140000000000001	0.0489439426945860	0.0246951145460053	9.7828394351841705	0.1335916239525892	0.3489434344464857	0.0653966904749147	
+4.8149999999999995	0.0566410924307036	0.0223164036835667	9.7970881993508385	-0.0675693254224724	-0.1368912058642852	0.1973108468878200	
+4.8159999999999998	0.0324426760612628	0.0302977681987956	9.8065096114425785	0.2637305906316214	-0.1204125465221114	-0.0419457315776718	
+4.8170000000000002	0.0433525006359919	0.0195213025435338	9.7829138133044378	0.0695975524244758	-0.0604925939795137	-0.0885805673429909	
+4.8179999999999996	0.0495545784298363	0.0251243516487904	9.7699610108128585	0.0329517158699965	-0.0116829396557886	-0.0918039841292240	
+4.8190000000000000	0.0615262937250414	0.0425225152596180	9.7950983208448967	0.1133185574766248	-0.0341273150284166	0.0490174647131607	
+4.8200000000000003	0.0449824604361905	0.0312660995209532	9.7896316139884600	0.0403108535087957	0.1429944679980215	0.1384387042299985	
+4.8209999999999997	0.0440749158103386	0.0276162247212457	9.7875698068244930	-0.1562483981093587	0.1026832201872874	0.1285214770996908	
+4.8220000000000001	0.0431804266021373	0.0128634538713451	9.7778495693411376	0.1384020204000170	0.1221311451873644	0.0235581929493107	
+4.8230000000000004	0.0466460333303141	0.0250810676347053	9.7991999843936792	-0.1313086236724013	-0.3035718483460763	0.0314164669226994	
+4.8239999999999998	0.0539610628356126	0.0229394390964951	9.7968530475197522	-0.2598435064538550	-0.1019796526119802	0.0863568561144664	
+4.8250000000000002	0.0186249775916748	0.0136532230932147	9.7865009389702138	-0.0538837055546970	-0.0216128252443916	-0.0255650321638593	
+4.8259999999999996	0.0551535800171527	0.0232918229371791	9.7891336733122483	-0.2020371046688468	0.1323533349012546	-0.0154833321129433	
+4.8270000000000000	0.0567108694668785	0.0119163534814566	9.7898465639814862	-0.0246792970028921	0.0231828873762799	0.0967686102898038	
+4.8279999999999994	0.0505929552297641	-0.0008478029052060	9.7978180350082766	0.0295575238849372	0.0961182091858007	-0.0060067127311599	
+4.8289999999999997	0.0635582376618522	0.0037034670061911	9.7941729324918825	0.1474874914184174	-0.1044398428808965	-0.1202732474654931	
+4.8300000000000001	0.0497945516877281	0.0118973187041996	9.8006672569715771	0.4743301425461931	-0.2104673676623581	0.1957665013160368	
+4.8309999999999995	0.0475363826463675	0.0204086786338795	9.8044614047440390	-0.0428761030429321	-0.2988144114093343	0.0151566955262842	
+4.8319999999999999	0.0486461273989637	0.0150503097244387	9.7749412310146369	0.1739088496812065	0.3614013622779397	0.0672354518699437	
+4.8330000000000002	0.0699979224822031	0.0386132022325998	9.8049720735792647	0.2999297752541343	0.1190000874351622	-0.0739958604537100	
+4.8339999999999996	0.0616208418285976	0.0107573804246083	9.7928559023573776	0.1372613529269463	0.1320799625392292	0.0904112808594507	
+4.8350000000000000	0.0483095459767042	0.0435727995338741	9.7774801693958153	0.1358374236831921	-0.0191278675174662	0.0247051047559494	
+4.8360000000000003	0.0596039613610912	0.0159171726151602	9.7811019301700242	0.1474020325068747	-0.3021053037698916	0.2106113095286013	
+4.8369999999999997	0.0426290261249338	0.0221330631351958	9.7951985644712973	-0.0727473884052435	-0.0151111685633405	0.2197838104369249	
+4.8380000000000001	0.0569542277616711	0.0185535896758406	9.7734353780193732	0.0513619436527945	0.0012348253498509	0.0539930051355670	
+4.8390000000000004	0.0703325384483368	0.0380684476074958	9.7759309483359669	-0.0258497200226914	-0.0668791221232486	0.2753930539882631	
+4.8399999999999999	0.0521390289605832	0.0082555048889132	9.8029108100231621	0.0602447971780609	-0.1205821338097779	0.1616636776982353	
+4.8410000000000002	0.0488639936872132	0.0423303944396627	9.7982959670302190	0.1328356931697075	0.0532865732934750	0.1882321006497636	
+4.8419999999999996	0.0498968892213119	0.0253908208874910	9.8007696308955516	0.1986075080645063	-0.2522545887915176	-0.0581518410937399	
+4.8430000000000000	0.0664315588163345	0.0258684578836898	9.7759171443015305	-0.1130120975818937	-0.0126352699482014	0.2533949124358829	
+4.8439999999999994	0.0414979392350382	-0.0016212322955521	9.7842154003029460	0.0441837017377485	0.1022633124981512	0.2930058582168705	
+4.8449999999999998	0.0545734841214357	0.0278967819880716	9.7860625886110792	-0.1081241207843902	-0.2238768359530465	0.1797879550517793	
+4.8460000000000001	0.0563207244575186	0.0137747335938204	9.7650378123872787	0.0117095671143932	-0.0818599461259585	0.0853840806769072	
+4.8469999999999995	0.0438575729291617	0.0225348523658111	9.8022378236461574	0.0794435581400337	-0.0836201988932572	0.1672267714807522	
+4.8479999999999999	0.0626436123235774	0.0230383899990544	9.8011873480655467	-0.3146387014489674	0.2032913666408434	-0.0020712759678972	
+4.8490000000000002	0.0460631582294672	0.0249960120577036	9.7775549325022446	0.0516256806950308	0.1541132707899145	0.1432818259874172	
+4.8499999999999996	0.0240793304213008	0.0394330964569754	9.7556935440022734	0.2024880490167687	0.2361082166148055	0.0267903994635340	
+4.8510000000000000	0.0468349747739718	0.0171355502675375	9.7921043618508552	-0.0890824781616343	-0.1870120378063898	0.0367421586325376	
+4.8520000000000003	0.0439508545110965	0.0323336809307563	9.7954375412615491	0.0420853690863533	-0.1579977029598708	-0.0525024527517613	
+4.8529999999999998	0.0502873263604130	0.0101979316410912	9.7820369194002872	-0.0370048821569870	-0.1317575545191550	0.3420740171572774	
+4.8540000000000001	0.0773030249466858	0.0135536181349462	9.8017463878376763	0.1686852717804411	-0.2499428214715916	0.0629354090421701	
+4.8549999999999995	0.0550587199658192	0.0396770618618161	9.7930024899918848	-0.0637541276197280	0.0650573033820913	0.1387297668999722	
+4.8559999999999999	0.0510818236123508	0.0169876542005331	9.7644717861713239	-0.0060278648329500	0.1191864535445745	0.0261493764020957	
+4.8569999999999993	0.0349328382947242	0.0293406689142093	9.7924662883165254	0.0475780102699178	-0.2288891653893894	0.0515403451835198	
+4.8579999999999997	0.0465860099449568	0.0182617575459592	9.7913632992746162	-0.0836227939381289	0.1922523485366112	0.1273975489389123	
+4.8590000000000000	0.0685464337398603	0.0104839085470950	9.8000726814315051	0.1310376745479462	0.1121018578771961	0.3386333871885565	
+4.8599999999999994	0.0413535815845773	0.0258792179862146	9.7901215382658808	0.2404197979377898	-0.1076254197204110	0.2249781170588291	
+4.8609999999999998	0.0546805106685612	0.0216542596035113	9.7747143267544647	0.3524631743748852	0.1172635402194735	0.1569480858132308	
+4.8620000000000001	0.0629499913842103	0.0299098591595079	9.8122577612293149	0.0238311307089350	-0.1017967931793695	-0.1224561294246356	
+4.8629999999999995	0.0563234168504591	0.0204092763071241	9.8017216203437130	0.3065750341315032	-0.1070051965696774	0.0901812424338253	
+4.8639999999999999	0.0435079008366659	0.0150447099616644	9.7746969543907056	-0.1114361462018326	-0.0803875059841195	0.0040827917876424	
+4.8650000000000002	0.0594961626229784	0.0230982053514945	9.8001396250030552	0.0415414870069156	0.1016810548436037	0.0300824513265031	
+4.8659999999999997	0.0515915177060602	0.0148024409850033	9.7716299774248263	0.0220109332733121	-0.3164804141306185	-0.0030119829164742	
+4.8670000000000000	0.0578872288758056	0.0461529636060464	9.7993350837412034	-0.1324790741247434	0.0171262642312543	-0.0893350363450509	
+4.8680000000000003	0.0761013440106598	0.0327859582032492	9.7863777657179423	0.2360136384143447	-0.1076419646643968	0.2055603587060350	
+4.8689999999999998	0.0517947894960528	0.0057207044287696	9.7725876235465190	-0.0823220492982357	0.0222122705400758	0.1695422881031823	
+4.8700000000000001	0.0590352939572516	0.0182759219389747	9.7892395313004616	0.2575335906345896	0.0573005678811760	0.0858002771157566	
+4.8709999999999996	0.0508874803695665	0.0261142363270506	9.7917628296923684	0.1878270407436088	0.0701249472060523	0.4360552616847986	
+4.8719999999999999	0.0514713223342578	0.0155783419123795	9.7810989152824579	0.1491782058171305	0.0704610965267380	0.2701315023742665	
+4.8729999999999993	0.0349267955580229	0.0127808767226769	9.7778783357969363	0.0652298536821335	-0.2389622083331575	0.1384489338267873	
+4.8739999999999997	0.0673161478662103	0.0280010572947160	9.7744081394680986	0.1613637035723104	0.1533309951486604	-0.1520189782362220	
+4.8750000000000000	0.0469049619220328	0.0381205868107263	9.7817264892767852	0.0148196353541480	-0.0272046821258898	0.0650823520549524	
+4.8759999999999994	0.0408736300155729	0.0169928324595190	9.7944068689244901	0.2918391421982302	0.1830022278135869	-0.0793396029088020	
+4.8769999999999998	0.0453533748182600	0.0144994423063265	9.8046667526242128	0.1052875475566618	-0.2632542487495984	0.1288705525767780	
+4.8780000000000001	0.0676536715073634	0.0293847486976549	9.8113132118993356	-0.0492026514516458	0.0767836470043906	0.1000597651150510	
+4.8789999999999996	0.0562642380403634	0.0340979888648183	9.8038301822049547	0.0387517348740206	0.0551498649347224	0.3097311183401674	
+4.8799999999999999	0.0660327505681839	0.0281523784442306	9.7772528144216118	0.4658849684763897	-0.1025461855822380	0.1472564247857345	
+4.8810000000000002	0.0312416985425044	0.0114957970111005	9.8005389957407587	0.2752887778733148	-0.0632890449765942	0.0119953333020169	
+4.8819999999999997	0.0440092067329498	0.0252328255008466	9.7821882247464345	-0.0326445541885431	-0.2234621665678596	0.1174233405270853	
+4.8830000000000000	0.0507067933281296	0.0334090292371517	9.7742949125094007	0.0661588795991975	0.0273239063518793	0.0164562359933812	
+4.8840000000000003	0.0517366752394359	0.0297916564477458	9.8039499208690479	-0.0711461504338615	0.2107448579945618	0.2623012829247398	
+4.8849999999999998	0.0474625400861409	0.0306517065913205	9.7861472737302417	-0.2091354193795512	-0.0200184884689444	-0.2025160451511245	
+4.8860000000000001	0.0782795627297386	0.0354489583015276	9.7920810670300362	0.1695599314639619	-0.0036255702956490	-0.0617744695949821	
+4.8869999999999996	0.0533865427185822	0.0274054909305617	9.8207845410441674	-0.1570619616129231	-0.0282043499768187	0.0024067105867333	
+4.8879999999999999	0.0685910133404280	0.0294530391425805	9.7894730944952304	0.0691248528132285	0.1835314136816523	0.0659455056325285	
+4.8889999999999993	0.0394723743684194	0.0354241393877280	9.7757412496971785	-0.1962275572482256	0.2729354665063501	-0.0071751869174921	
+4.8899999999999997	0.0495347732661064	0.0221855034830436	9.7992599755304308	0.1311777024342789	-0.0015245601356930	0.2794340892005094	
+4.8910000000000000	0.0452406656592383	0.0246867801330118	9.7953757837408428	0.2818687709876913	0.0168062153279149	0.0797684781098150	
+4.8919999999999995	0.0515084469652903	0.0099689114669856	9.8010496361042740	0.3275987631803261	-0.0772356132337698	0.0649781529840445	
+4.8929999999999998	0.0598207592792438	0.0167890591803094	9.7920825178983968	-0.0951080997388773	-0.0843309257358464	0.1972996461191989	
+4.8940000000000001	0.0490113742398377	0.0281477945453480	9.7652448630298387	0.0646340665037675	0.0377576448372208	0.0228091140425716	
+4.8949999999999996	0.0519513090037644	0.0098566613096643	9.7871545219089917	0.4292107731936284	0.1431444693392850	0.0668198325268821	
+4.8959999999999999	0.0404216668411856	0.0287150766139619	9.7976707524959572	-0.1022299734662225	0.0491896624852713	0.2829429691854247	
+4.8970000000000002	0.0409928747703439	0.0234406517189921	9.7870976487594668	-0.1205626875494002	-0.2393898570840911	-0.0696377564497699	
+4.8979999999999997	0.0662286216991960	0.0134098124946903	9.7900263419567910	0.1553964811197082	0.0995103006382799	0.2993557418369741	
+4.8990000000000000	0.0531966156565074	0.0248331462829269	9.7583114426998101	0.2481022918933903	-0.1107689470524809	0.1745968245042480	
+4.9000000000000004	0.0635577964300052	0.0215927971704183	9.7734974820106153	0.0836464632296070	0.0292773518075467	0.1156604071788676	
+4.9009999999999998	0.0708927804941190	0.0368195189079600	9.7940577248204388	0.2845739071744871	-0.0807444836820663	0.0509153783261539	
+4.9020000000000001	0.0688060170691305	0.0348896926357090	9.7758414478086078	-0.0559353837899410	0.0550225997829911	0.0102939197959392	
+4.9029999999999996	0.0415507947479870	0.0415993249150593	9.7943710694135948	0.0924174420475487	-0.1180240251522139	0.0614289700381250	
+4.9039999999999999	0.0310853869870066	0.0248840037678728	9.7972732741351383	-0.0503899249150601	-0.0909584676074931	0.0379800417714761	
+4.9049999999999994	0.0399271987302897	0.0191135274837436	9.7796165023742301	-0.0947418388300875	-0.0007176984803650	0.1550637700381538	
+4.9059999999999997	0.0544439234380278	0.0260925708034565	9.7800285949739063	0.0375102780393567	-0.1593636393309464	-0.0410293684171319	
+4.9070000000000000	0.0575058594485726	0.0282322988982821	9.8117420815469192	-0.1201411150521253	0.0165096576815403	0.1949814859468942	
+4.9079999999999995	0.0522361700456860	0.0345953895777605	9.7699296316089086	0.0713939123034267	-0.1833173957119257	0.0950214137925660	
+4.9089999999999998	0.0572056819641245	0.0227985797382360	9.7871346034084468	0.2689491926184998	0.0181652510558006	0.3264039929321180	
+4.9100000000000001	0.0473929874047206	0.0211867179144194	9.7968652910689329	0.1513357622227639	-0.1924754142230469	0.1102414805125935	
+4.9109999999999996	0.0425722366100698	0.0112252389139676	9.8012420300287229	0.1460792517542274	-0.0034354807225620	0.0979806630748133	
+4.9119999999999999	0.0518944098984309	0.0219784288633624	9.7853462236185074	0.2226756456756592	-0.0129026178863885	0.0920749812873499	
+4.9130000000000003	0.0512260045102732	0.0019036100288513	9.7919353370448672	-0.3455742370059098	-0.1921764368417157	0.0581489426240370	
+4.9139999999999997	0.0440356618908447	0.0184565584262078	9.7949230363961259	0.2702154547952015	-0.2279313656907439	0.3090868883252265	
+4.9150000000000000	0.0583167347567278	0.0041709161647774	9.7981908485284723	0.1205000553144127	-0.1660938782346627	0.3375166759205057	
+4.9160000000000004	0.0544963494231223	0.0450191203462630	9.7794359474954327	-0.3536591326265461	-0.0951985556424046	0.2326227275213363	
+4.9169999999999998	0.0466100828959804	0.0298803280057746	9.7700814125708639	-0.1402683364328439	-0.1183131104595028	-0.1812056042690049	
+4.9180000000000001	0.0564005748138245	0.0222352705820012	9.7895880873355470	-0.0194327996566782	-0.0647705219072123	0.0890122867384985	
+4.9189999999999996	0.0634468023210207	0.0193859154093460	9.7977946522864201	0.1906194293846094	0.1063623477827107	-0.0253280391643407	
+4.9199999999999999	0.0590665548646925	0.0395260587382950	9.8272326985989782	-0.0899311743891944	-0.1620670314839569	0.0954606886973467	
+4.9209999999999994	0.0432311343436025	0.0032588500941818	9.7759856425335041	0.0978683541235315	0.1714066544719220	0.2184173438213454	
+4.9219999999999997	0.0625833332106705	0.0354341324451259	9.7832670920246443	-0.1153046753601904	0.0732539261887164	0.1099628268742106	
+4.9230000000000000	0.0536263178425253	0.0180463436853938	9.7699679276556317	-0.1837623410307536	0.0603445180445914	-0.2338358547441997	
+4.9239999999999995	0.0615124619567613	0.0239490857972238	9.7886584937144718	-0.2304105389108878	0.0663988246273528	0.3033798093110546	
+4.9249999999999998	0.0438630410297886	0.0095585078394923	9.7819839199818297	0.1066066263166794	-0.1596379793580513	0.2537111932137491	
+4.9260000000000002	0.0758217313410211	0.0353081622910555	9.7791214834982743	0.2591217217133258	0.0655197376804168	0.0764295060998832	
+4.9269999999999996	0.0823563627961087	0.0428926827036929	9.7719014490322440	0.3162223136357039	-0.2187726060718026	0.1600824614407134	
+4.9279999999999999	0.0579562047617076	-0.0039961014877122	9.7865300896631631	0.0454988904836694	-0.0876384947116716	-0.2205857259957307	
+4.9290000000000003	0.0657987577716935	0.0117731306144689	9.7876604696396718	0.3898054852207765	0.1712578405345778	0.2312703706602109	
+4.9299999999999997	0.0494231780533039	0.0166321798641711	9.7582261028084751	-0.1982652241178504	0.0369337362983922	0.1774065219530955	
+4.9310000000000000	0.0499899702249258	0.0344075752284112	9.8088252968640557	0.0859323777166388	0.0864711053126524	0.1968832155062333	
+4.9320000000000004	0.0668936491308441	0.0271416705902375	9.7980638455302316	0.2067211389192699	0.0951795849395301	0.1296104470252900	
+4.9329999999999998	0.0528169425799165	0.0015853928414351	9.7820069264604985	-0.0119721049285935	-0.0669257746651632	-0.0329626586227039	
+4.9340000000000002	0.0831758085630761	0.0231294200063225	9.8036838979758478	-0.3294803901467285	0.0795933454724279	0.0686828724700778	
+4.9349999999999996	0.0509457491185935	0.0196064389525724	9.8169213533081354	0.1388386022971781	-0.0923455737208874	0.0991875950791996	
+4.9359999999999999	0.0427340687247450	0.0324524131402059	9.8063032800299386	0.2422126839390796	-0.2896756154940113	-0.0608709135720707	
+4.9369999999999994	0.0537417347835242	0.0152228433333547	9.8045671967813117	0.0139790257579295	-0.1274408598025861	0.0771273008086944	
+4.9379999999999997	0.0406915138158138	0.0146707293425008	9.7778498348489222	-0.2614212480349452	0.1639247698331689	0.1044623482526263	
+4.9390000000000001	0.0532365744974076	0.0048616783922648	9.7815373812805291	0.2116021412249233	-0.1570514387500375	0.1276216393946217	
+4.9399999999999995	0.0481683400967054	0.0357140817066341	9.7667565300179788	0.1156219372886640	0.1486230689468522	-0.2635514870791797	
+4.9409999999999998	0.0425617147849620	0.0391958299086631	9.8014761783947861	-0.2779323393063012	-0.1431365193929122	0.1269242067035214	
+4.9420000000000002	0.0422584267188111	0.0257255480404153	9.8085862146800729	-0.1069846743422055	0.0458589814617848	0.1785766183569342	
+4.9429999999999996	0.0709381470419455	0.0269138441491186	9.7678654905454927	0.0460322588175831	-0.0645088723409962	0.1358054361472974	
+4.9440000000000000	0.0458375343532362	0.0213425305495959	9.7849214781385836	-0.0680861500589755	-0.0816900108976839	0.2007665706020644	
+4.9450000000000003	0.0610402568300694	0.0045621549716911	9.7763876739259228	0.0121761169278826	-0.0256336045145421	-0.3207064817644311	
+4.9459999999999997	0.0608347314935894	0.0456951596205156	9.7823018971828137	-0.0069571461069444	-0.1522472821335280	0.1165842861279671	
+4.9470000000000001	0.0311916585376417	0.0292104299105065	9.8017975869455842	0.1984389444563662	-0.0150791921709365	-0.1964149429574796	
+4.9480000000000004	0.0335184234339103	0.0255042955192336	9.7679231280344663	0.2385745476348682	0.1870903634006546	0.0579945643245220	
+4.9489999999999998	0.0726498997207637	0.0141195249924704	9.7662524811847007	-0.2558703111986582	0.0055214001571645	-0.0352501626675521	
+4.9500000000000002	0.0453063487781250	0.0309115333995286	9.7752604903843494	0.3383990197689485	-0.0828892025721899	0.3371629385714039	
+4.9509999999999996	0.0710952512267408	-0.0024509217140215	9.7982915219061510	0.0637997754524366	0.0866804961780754	0.1278272004191013	
+4.9520000000000000	0.0532639318118626	0.0400451478730185	9.8123501648342089	0.2076746863790674	0.0400656685599594	0.0970873385272813	
+4.9529999999999994	0.0705562625688448	0.0195254310749583	9.7990015231496237	-0.0077281010128886	0.2529923368566149	-0.0328233566542892	
+4.9539999999999997	0.0598814400182466	0.0336254889525351	9.7794857512988838	0.1534248068506089	-0.1119824203757775	0.1957307919739870	
+4.9550000000000001	0.0570363545406404	0.0176787563162887	9.7916406238590863	0.1332516455266760	-0.1592674957355830	0.0718069223739595	
+4.9559999999999995	0.0523828417385187	0.0451563343948948	9.7874245642777460	0.1950262854293986	-0.0296827662557208	0.1988953939661695	
+4.9569999999999999	0.0744219223991200	0.0249320087217502	9.7717825719532119	0.0494319513999150	-0.1491142069055644	0.0876908825253729	
+4.9580000000000002	0.0312687612604529	0.0263992064562360	9.7714519822108112	-0.1660947352236606	-0.1040840241226761	-0.1119716971561494	
+4.9589999999999996	0.0706838918374260	0.0376906398274661	9.8079657701639835	0.2017502977236420	-0.0182674996321832	0.1490750847487008	
+4.9600000000000000	0.0557079013981657	0.0292189682429872	9.7936825934408756	0.1393516401432639	-0.1756577514363790	0.3535231438326988	
+4.9610000000000003	0.0510864622980731	0.0179854415276584	9.7999244045179896	-0.1222933812216612	-0.0680860989393388	-0.0971003954902248	
+4.9619999999999997	0.0520563058619057	0.0440717769023296	9.7981794928935848	-0.0209426938932380	-0.2047671507946683	0.0875152436149114	
+4.9630000000000001	0.0571359399563717	0.0431601500990078	9.7898800128523646	0.0646261570308828	0.2262843998033644	0.0621553324937028	
+4.9640000000000004	0.0752359899764153	0.0082350699856622	9.7853841346990436	-0.2049959733827452	0.1963897334856941	-0.0011671892081919	
+4.9649999999999999	0.0557164546567966	0.0076858348470819	9.7967849274172263	-0.2966397828470940	-0.2006884115261218	0.3109884824454028	
+4.9660000000000002	0.0661345135406387	0.0267791468026342	9.7865242887145172	0.0819835981335202	-0.1557587921172278	-0.1003201223599810	
+4.9669999999999996	0.0342677212343483	-0.0061832787283596	9.7997769185973755	0.2472058738653791	0.0996019356360178	0.1955381009484277	
+4.9680000000000000	0.0675648351359238	0.0375017537238137	9.8034559813871542	0.1385414036580512	-0.0004496185335152	0.0822518643884108	
+4.9689999999999994	0.0600587258381041	0.0092219750448692	9.7761192619503436	-0.1014154534577842	0.2496957325681531	0.0648179709173309	
+4.9699999999999998	0.0734601712228368	0.0337586482809162	9.7830264693179831	-0.1162231860297652	0.2125467569190619	0.2041327597456404	
+4.9710000000000001	0.0633382453522695	0.0177526347684139	9.7784732646249353	0.4060490605638178	0.0156669315356864	0.3043080800445498	
+4.9719999999999995	0.0508314243147153	0.0211883130718510	9.7964278603500254	0.1140662645685598	-0.3137757254118663	-0.1395204734660376	
+4.9729999999999999	0.0477576135896408	0.0324326279300134	9.7900882853876272	0.1863864322680532	-0.0039939113590968	0.1249810544942685	
+4.9740000000000002	0.0646484123800460	0.0422465749032763	9.7823363194477118	0.0309111476792080	-0.0409153026523411	0.0819126255446839	
+4.9749999999999996	0.0609397275525674	0.0389757136500759	9.7790637898565205	-0.3378118879840757	0.1478425887731242	0.2253277292010011	
+4.9760000000000000	0.0335369151442781	-0.0019020732758948	9.7948143581708482	-0.0511522487329241	0.1065803241845531	0.2965279660688740	
+4.9770000000000003	0.0467934498714389	0.0139507946455850	9.7866322604801006	0.2060653623949091	0.0284113768778137	0.2462007005945237	
+4.9779999999999998	0.0672046196929139	0.0111069933262665	9.7810755561319631	0.2589214853413175	-0.0720695144964295	-0.0440031643767038	
+4.9790000000000001	0.0701194732827319	0.0271761307512244	9.7875571410497830	0.2225401116873103	-0.0655102860299996	0.4232320409285737	
+4.9800000000000004	0.0368475738244076	0.0240454856143332	9.7874506479643060	0.0063061437022458	-0.1062098402949293	0.0067713056263875	
+4.9809999999999999	0.0620530920862433	0.0313975463968704	9.8028246703891462	0.1423732567140430	-0.0231830724716924	-0.1233563231698295	
+4.9819999999999993	0.0616481281697316	0.0391087769076196	9.7874010147622048	-0.0344039241080310	-0.2423046756965175	0.1030038582597201	
+4.9829999999999997	0.0536319872637548	0.0302944761116209	9.7583378500092017	0.0060076678071542	0.0174284302409682	-0.3301248433211524	
+4.9840000000000000	0.0536832285926001	0.0263943551486717	9.7900357491505510	-0.0690567431385515	0.1414683850224228	0.5342689901746147	
+4.9849999999999994	0.0654633497972194	0.0307379315702415	9.7883579529915057	0.3144691493819797	0.0916712096296609	-0.1013579173428429	
+4.9859999999999998	0.0441456666820211	0.0081135545814318	9.7916897367515094	0.0433934078529795	0.1066773338006323	-0.0757344042692079	
+4.9870000000000001	0.0609949249332979	0.0088964596060659	9.7807623334792115	0.1814689210278714	-0.0402713687702381	-0.0010067141102435	
+4.9879999999999995	0.0611510494312206	0.0164348178589720	9.8022756798671384	0.2801730457758959	-0.0111950087305571	-0.1572645289418712	
+4.9889999999999999	0.0648853205771653	0.0265795494270593	9.7900338404991167	-0.2571595155523193	-0.2175468286951516	0.0129283332216069	
+4.9900000000000002	0.0420482746899755	0.0352927799271095	9.7847016235399362	0.2619762928114891	-0.0975778258635102	0.3118140437632161	
+4.9909999999999997	0.0647491931036064	0.0105389058231722	9.7851485298514849	-0.0076527392593281	-0.0509478785965696	0.0596507946228976	
+4.9920000000000000	0.0767237785386301	0.0475959997444807	9.7999259593530557	0.0894079875342363	-0.1778731487518202	0.3080786508070629	
+4.9930000000000003	0.0338676959559913	0.0210243694443703	9.7763443575736932	-0.0462054827756855	0.0294619196499751	-0.2083318658062643	
+4.9939999999999998	0.0575996338537520	0.0324753604166127	9.7831779572863393	0.0456635166824243	0.1951683434887573	-0.0441214735621876	
+4.9950000000000001	0.0447121427246488	0.0234793686309780	9.7710357264980097	0.3586388805896759	0.0767922123310026	0.1295322643216208	
+4.9959999999999996	0.0554151051699041	0.0173570712771706	9.7930657361939364	0.2168657764984190	-0.1146700969934659	0.2541604719599557	
+4.9969999999999999	0.0818966137581972	0.0034184689757937	9.7890871085410485	0.0007397182700758	-0.0513978308458494	-0.0142600784381179	
+4.9979999999999993	0.0628405092699505	0.0293023138783707	9.8034170342204465	0.0986796794385841	0.0437835466721712	0.0832618851590485	
+4.9989999999999997	0.0493811353207941	0.0255667535090161	9.7655432831296771	-0.1206156973791046	0.1953123072197388	0.0762203789560885	
+5.0000000000000000	0.0432434544696310	0.0051157709341127	9.7964362651511614	0.0093510192636835	0.2000162282098236	0.1777902288946206	
+5.0009999999999994	0.0575943980521653	0.0182529415392922	9.7919037734787935	-0.0465530694216585	-0.2224936308786547	0.1634643130290933	
+5.0019999999999998	0.0461184201924238	0.0107834008903768	9.7945011645650553	0.0245375538481394	-0.0700618415607826	0.3090231722866185	
+5.0030000000000001	0.0387829970106135	0.0078867749501580	9.7784345164180575	0.3120416807638484	0.1000022349836276	0.2919693559880860	
+5.0039999999999996	0.0505458567468371	0.0086537628053425	9.7892317902432087	0.1733083900367955	0.0833626135638880	-0.0359809170295995	
+5.0049999999999999	0.0589572455049649	0.0288900931698991	9.8064380678939180	-0.1488061069923604	-0.1442593502819372	-0.1372989622682048	
+5.0060000000000002	0.0580398137094263	0.0572656594772417	9.7858923678321830	-0.0105944333761138	0.2144892250369813	0.1609386772861597	
+5.0069999999999997	0.0486162778646096	0.0120711417598061	9.7867235562706156	0.4165476889422498	0.2946006963783437	0.1650603823212645	
+5.0080000000000000	0.0506777328875127	0.0005537328252906	9.8142784567200145	0.0520885160737328	0.2713458108917373	0.1292072358722694	
+5.0090000000000003	0.0509779158689527	0.0488309112247455	9.7875642690689073	-0.0878162266053913	0.0013844494385054	-0.0615114303912120	
+5.0099999999999998	0.0772984430759408	0.0500657420299529	9.7924174668395221	0.2422180153137146	0.1419167115360369	0.1882184816471519	
+5.0110000000000001	0.0581192267695663	0.0055997611917355	9.7888247339135024	0.0351888988535888	0.0262329486236893	0.0499496308249186	
+5.0119999999999996	0.0700740103915560	0.0546074324617414	9.8022951616030074	-0.2223356996314940	0.0093531660133023	-0.0618870772069674	
+5.0129999999999999	0.0483853172952935	0.0318895479792885	9.8065516602225422	-0.0273883777511665	0.0208831580787272	-0.1203417223940252	
+5.0140000000000002	0.0687827624991513	0.0133142225209173	9.8039648654866767	-0.1285200258247684	-0.3213018023227093	-0.0089617190810230	
+5.0149999999999997	0.0614651293987702	0.0239249243343580	9.7902606467316549	0.1264115854349437	-0.0914769811979563	-0.0238012476960078	
+5.0160000000000000	0.0552199347451281	0.0393893536718734	9.8041955072087728	0.0722196346491780	0.2202883921319023	0.0560325428924713	
+5.0169999999999995	0.0380980625538687	0.0201536081804384	9.8090104692206594	0.1922342918138521	-0.1209477485781558	-0.0505948361500784	
+5.0179999999999998	0.0463477594866511	0.0189007556146013	9.7926895629838810	0.1946848433705262	0.2479265526363858	0.0480768469805362	
+5.0190000000000001	0.0768106196875471	0.0194241810131871	9.7794046632049589	0.2835428571417346	-0.0691844223169551	-0.0173407410978705	
+5.0199999999999996	0.0880852752872348	0.0272844145508651	9.7974766406922313	0.0462565499307645	0.1427027758255482	-0.1023583033231136	
+5.0209999999999999	0.0642297314129255	0.0487416577474916	9.8175025655658335	0.2251751106345360	-0.1115322914940967	-0.0476142863809113	
+5.0220000000000002	0.0705802394985554	0.0143873755482029	9.7945279817555519	0.3581175700033620	-0.2395279888722730	-0.1280538377338421	
+5.0229999999999997	0.0716577597458185	0.0372806417247890	9.8115576635057611	0.0451431748865321	-0.0394578923210654	0.1409926947849031	
+5.0240000000000000	0.0569599054509166	0.0271325184355871	9.7974301856679702	0.1157050665037769	-0.1083595250571994	0.2221688040029059	
+5.0250000000000004	0.0593706040122339	0.0368278072258040	9.7931069385155105	-0.0135990671967533	-0.3821716637289682	0.0976660816793183	
+5.0259999999999998	0.0587217617573704	0.0419962764156533	9.7955563820548921	0.0585702733551479	0.1136746209388460	0.2221433073902653	
+5.0270000000000001	0.0547944976901092	0.0303258280285977	9.7839441517605081	-0.1264988768534714	0.3107152281816107	0.2641998482157204	
+5.0279999999999996	0.0394778748033150	0.0296725464807691	9.7750726887767581	-0.2407728839841355	0.2378465199353977	0.3674729568216896	
+5.0289999999999999	0.0958917444502559	0.0124140629646658	9.7921468131532450	0.0851569884387601	-0.2405111084364606	0.0379737520666664	
+5.0300000000000002	0.0511264246614087	0.0071656295592766	9.7970296718709040	-0.0362982987585809	0.1540468131245311	-0.0290204668824309	
+5.0309999999999997	0.0328848495086027	0.0313125619111516	9.7813092038831826	0.1984228244365199	-0.0260228835587473	0.0271821315144142	
+5.0320000000000000	0.0598697401143425	0.0107280151344156	9.7689546839376948	-0.0481780035630200	-0.1268999315573995	0.1594487159371801	
+5.0329999999999995	0.0438334299266054	0.0257025665722032	9.8018456825506028	-0.0863837390201328	-0.2432125400898027	0.1002941538663847	
+5.0339999999999998	0.0582674246235303	0.0422725355063750	9.7885172384433439	0.0639311653327903	0.3927757067062747	0.0500007744100297	
+5.0350000000000001	0.0780016340063486	0.0150044150181315	9.8034586405517814	0.1954601275507156	-0.0090978759198765	-0.0337999414613334	
+5.0359999999999996	0.0522776360703371	0.0104290469375936	9.7976003338306761	-0.0123548100977676	-0.0155517415085539	0.0064565344701129	
+5.0369999999999999	0.0455654638293200	0.0172691813970088	9.7978503362328286	-0.2899539462832408	0.0563382127585775	0.0090189754873721	
+5.0380000000000003	0.0632104973372777	0.0085325798769392	9.8001962646872087	0.1438291247862066	-0.0031855565222799	0.2618378757033377	
+5.0389999999999997	0.0697925809014737	0.0093144100254721	9.8150913003103568	0.4258362687399097	-0.0127823380720159	0.0826757606972107	
+5.0400000000000000	0.0605008304840829	0.0337238105540425	9.8104406854335267	-0.1100125885281718	-0.0045341834804465	0.2251436956481815	
+5.0410000000000004	0.0539037729679721	0.0032443005066567	9.7882488181486629	0.1282555821659067	0.0037763176681656	0.0153074014239470	
+5.0419999999999998	0.0805449825021295	0.0322819359052032	9.7886928762661167	0.1341818871758268	0.1790349778058049	0.0521459338183174	
+5.0430000000000001	0.0622362519074751	-0.0017023451559981	9.8094200932699565	-0.1122658769711360	-0.1298307887140192	-0.0175706418278242	
+5.0439999999999996	0.0420159841028356	0.0239672690588970	9.8070959436863383	-0.1109146112402959	0.1810549039597062	0.3025507161933709	
+5.0449999999999999	0.0798062519173820	0.0265675139216340	9.8173533326571487	0.0631687487623036	-0.2584694469793526	0.0180672878463824	
+5.0459999999999994	0.0486464680659393	0.0226690729119664	9.7970972601313893	0.0912591700709340	-0.0981196610727667	-0.0000309860141943	
+5.0469999999999997	0.0619381204171955	-0.0027341772918108	9.8126444544990488	-0.0199071155562609	0.0071237218721848	0.0634463619267177	
+5.0480000000000000	0.0474483848813391	0.0302141556595960	9.8052510027807909	0.0065615688503210	0.0478703611523367	-0.1853672677775113	
+5.0489999999999995	0.0561927791329191	0.0252669356438527	9.8006307364316552	0.0298265369611631	0.0216720000420760	-0.1102431809511174	
+5.0499999999999998	0.0473411165464947	0.0088797611268838	9.7776504437212157	-0.0227703781964995	-0.1451309407955040	0.0418083761648671	
+5.0510000000000002	0.0475283377579490	-0.0086556238053238	9.8024000976931571	-0.0800768016512190	-0.1507777966227385	0.4488728061942981	
+5.0519999999999996	0.0592515588664859	0.0247969554009696	9.8030242665977045	0.1638636471994415	-0.1053155399732053	0.4094272208636482	
+5.0529999999999999	0.0613540720100929	0.0424553367299753	9.7870470755104826	0.1407309897358803	0.0417909954751809	0.1053686603061703	
+5.0540000000000003	0.0640895612540024	0.0309223882267484	9.7859973298731582	-0.0066011561083195	0.0769227420939236	0.1105887431177462	
+5.0549999999999997	0.0518933593748459	0.0171098179037745	9.7949178816194511	-0.1292588407066834	-0.1028202183933550	0.0530423167392443	
+5.0560000000000000	0.0697158143864158	0.0445410543736798	9.7786624578291867	-0.0434640067662613	-0.2335510816599675	0.0770963481822188	
+5.0569999999999995	0.0915883516957899	0.0249318447362185	9.7778968399596096	-0.0472247582595827	0.0344952645971094	0.4249705187802872	
+5.0579999999999998	0.0619767782437883	0.0386368412098136	9.8040465642215864	0.0007664224431358	0.0610362705382692	-0.2292158559749143	
+5.0590000000000002	0.0418733923199049	0.0186928192307349	9.7934407618221098	0.2605819145881918	0.0221621529141757	0.1209856454476396	
+5.0599999999999996	0.0809204549056320	0.0192894544437775	9.7941619347365307	0.0905144593244391	0.1027560147142985	0.3757733258209405	
+5.0609999999999999	0.0608364201701706	0.0356688768863924	9.8029655343530049	0.3124269236779252	0.0883552106686184	0.2128463948985400	
+5.0619999999999994	0.0710005221987111	0.0189223623296448	9.8153258425189023	-0.2234101210220969	-0.0482425041098925	0.3953230143011272	
+5.0629999999999997	0.0773214017081596	0.0178560424734958	9.8115948423808241	-0.0779333631630423	-0.1775244259418862	0.1240494558174666	
+5.0640000000000001	0.0540952933047379	0.0289846215483330	9.7884087177949315	0.1756057002165705	-0.0336823387604418	0.0154339586983906	
+5.0649999999999995	0.0381294231362154	0.0104515226176355	9.8051390189062850	0.2475159705740977	-0.0133025748079162	0.0525941450607787	
+5.0659999999999998	0.0726980721827820	0.0349768910958034	9.7910527688790445	-0.1363915748997224	-0.0976044206313539	0.2776552429992506	
+5.0670000000000002	0.0774842766923548	-0.0034376423908755	9.8111940187405171	0.2086648721499962	-0.0439801387711812	-0.1796079665539583	
+5.0679999999999996	0.0630406365826396	0.0056530720382569	9.8003909492518630	0.0451179844624198	0.1875547294068796	-0.0498474495004405	
+5.0690000000000000	0.0510905870542156	0.0359765091973668	9.7989548160665425	0.1687606515692038	0.0366377734904284	0.2100898858679948	
+5.0700000000000003	0.0494809023338088	0.0168893419140256	9.7985761007766996	0.0993550810009478	-0.0258108851726896	-0.1046126309160989	
+5.0709999999999997	0.0305132768771184	0.0471215038502650	9.8056022955306101	-0.1214915305101478	-0.0836780092781388	0.1392534548150065	
+5.0720000000000001	0.0502038244970586	0.0332716641080153	9.7979714797031363	-0.1114188288011822	-0.2255079819437386	0.3104227417563386	
+5.0729999999999995	0.0739522820625683	0.0399482468735941	9.7875053232011187	-0.0918385182429870	0.0629716486137691	0.2407993818417018	
+5.0739999999999998	0.0500811348312097	0.0232088068746244	9.7628222885582279	-0.0848370068862563	-0.2033958022074119	0.1417563807145725	
+5.0750000000000002	0.0552809313984861	0.0246690323508871	9.7947042446668604	-0.0628462076849372	-0.0463984813325234	0.1802283043021595	
+5.0759999999999996	0.0764190588276567	0.0331595508162528	9.7906875101045454	-0.0277309607331961	-0.0027555926690199	0.1711361701530242	
+5.0770000000000000	0.0668912863964631	0.0253735587890740	9.7822265780478528	-0.0841809479604165	-0.2269975449286880	-0.0931898164637362	
+5.0779999999999994	0.0701121057727169	0.0418244633531633	9.7998644669529327	-0.0599690604677812	0.1367589386199101	0.1715514636542055	
+5.0789999999999997	0.0582812050324724	0.0093251932696906	9.8056633373125255	-0.0880855055663142	0.0463362899044326	-0.0053606282856378	
+5.0800000000000001	0.0323567181510499	0.0240427409424739	9.7944231599991678	-0.0298596763889405	-0.2124475465988989	0.0178933248556131	
+5.0809999999999995	0.0648837998858200	0.0349090516244704	9.7902415536201097	-0.2544134317085628	-0.2689109161113754	0.2459211330782506	
+5.0819999999999999	0.0601282963466308	0.0357602342540084	9.8052907854361990	0.0215807493506639	-0.0516632812896668	0.0246076446578501	
+5.0830000000000002	0.0568278890701229	0.0014588644854772	9.8237522295980195	0.2737954024695403	0.0514741974267186	-0.0543891301007663	
+5.0839999999999996	0.0596702091201694	0.0396638926722652	9.7988812845468445	-0.0384187426112529	-0.1337213969747421	0.0582883118039082	
+5.0850000000000000	0.0572150625891068	0.0262832587565128	9.7775291072902650	0.0490321237128987	-0.2101925844189710	0.1414937656119127	
+5.0860000000000003	0.0704415371222723	0.0175159849682358	9.7992863398468160	0.1335162864910576	0.0557905612422591	0.2993791678602311	
+5.0869999999999997	0.0744838339017220	0.0093760471922863	9.7864497015158829	-0.0105143542675192	-0.0875865935523627	-0.1400186291479044	
+5.0880000000000001	0.0630420559614205	0.0181432294128841	9.7833318080515870	-0.0685861334065186	0.0552463444212943	0.0534020485928036	
+5.0889999999999995	0.0924142838798230	0.0035762737560569	9.7989417787872579	-0.1243599261744554	0.0130412225512048	0.2276551296715145	
+5.0899999999999999	0.0720266398021110	0.0302734697565411	9.7863475103138455	0.0069609255829617	-0.1787750729039675	-0.0135236310150208	
+5.0910000000000002	0.0662411430849050	0.0210554545459585	9.8032134582150974	0.0034919002069522	0.0843002420457478	0.4505379987096295	
+5.0919999999999996	0.0709364331929589	0.0296262649429988	9.7963251318338092	-0.0778631114624904	-0.0901076935823073	0.0073911868259727	
+5.0930000000000000	0.0289073425748133	0.0352576857207832	9.7948700340132433	0.0858625224849021	0.0489384725904422	0.2364590873219009	
+5.0939999999999994	0.0652534591464938	0.0456084970011440	9.8039523429285893	-0.0405777912205951	-0.1400231625785524	0.1812454321801740	
+5.0949999999999998	0.0578040795751093	0.0235506177417140	9.8021039644675305	-0.0580058483751011	-0.0772275661766296	0.1174952800633072	
+5.0960000000000001	0.0506883611648001	0.0337831791323824	9.8002618543807660	-0.0625200249680627	0.2369963469476134	-0.0303345779432096	
+5.0969999999999995	0.0685019738231523	0.0491005881725548	9.7900804141252973	0.0873361568025818	0.0635923096630938	0.2266112904084972	
+5.0979999999999999	0.0636196629484939	0.0120677204033479	9.7941076657786130	-0.1775782968571341	-0.2515869797085356	-0.1010026515908517	
+5.0990000000000002	0.0540906796457946	0.0244815458302226	9.8032938444736804	0.2113768597449321	-0.0723956433572583	-0.0332717294924067	
+5.0999999999999996	0.0594463663877615	0.0177659936169452	9.8082201653385290	-0.0735091535427810	0.1917915919724682	0.1115004229910900	
+5.1010000000000000	0.0455161356744183	0.0091575094829684	9.7917176518416937	0.2048054373281309	-0.1597548529933500	0.2525847172882335	
+5.1020000000000003	0.0557455595598795	0.0127146568874625	9.8052969825501979	0.0727655325768449	-0.2415979939109134	-0.0758120162035682	
+5.1029999999999998	0.0459566536820927	0.0220360186237521	9.7865970861223648	0.0938464014613144	-0.0269789329606805	0.3431677361469489	
+5.1040000000000001	0.0683260864821211	0.0190665901091467	9.8170754172668762	0.1348112136787363	0.2121470169785085	0.1204366501093304	
+5.1049999999999995	0.0769924578785938	-0.0065149692857584	9.7763545451001139	-0.0160946129558700	0.0718441124824798	-0.0552519519407028	
+5.1059999999999999	0.0721388243080439	0.0130481441795585	9.8080842520786398	-0.0208751745047784	0.1113041797052329	0.0336786770053344	
+5.1070000000000002	0.0556997378302213	0.0317662567236243	9.7832182406468977	-0.0738724600442060	-0.2307976936209266	0.1418571911574985	
+5.1079999999999997	0.0653179298322176	0.0479228567228114	9.7799527219496909	0.0698678538038952	0.2146173319731874	-0.0424309911577928	
+5.1090000000000000	0.0414719062632987	0.0129383479910168	9.8041811880659626	0.1332562553884125	-0.2260322105588267	-0.1875515864899595	
+5.1099999999999994	0.0638883640207572	0.0463002872303135	9.7909819052984499	-0.0242756576293480	-0.1650412604555239	0.1811388934820610	
+5.1109999999999998	0.0732484253931665	0.0248791464495285	9.8163923049020614	0.1289684819741014	0.1031855552094433	0.0841896998698762	
+5.1120000000000001	0.0681271948420150	0.0311539544709236	9.7887554613664118	-0.0957311568694676	-0.3002497780343887	0.0470239461782469	
+5.1129999999999995	0.0584625976736716	0.0252448620303815	9.8207626414561666	0.1474265291403211	0.0477461949317534	0.0574456390796049	
+5.1139999999999999	0.0768944939449756	0.0229136690056094	9.7894028782361158	0.1203413711687421	0.2714257715304546	0.2706146780917569	
+5.1150000000000002	0.0717653520200470	0.0162896306973837	9.7949666941379121	0.0959492456016369	-0.0758050876230833	-0.2488888201956474	
+5.1159999999999997	0.0892180665859302	0.0305144322264062	9.7960836303975167	0.2703580584145233	0.0278023196408065	-0.0379867402270606	
+5.1170000000000000	0.0536228688565485	0.0307428702461058	9.8018898869322939	0.3788583765003602	0.2236166288042074	0.0172755287704119	
+5.1180000000000003	0.0527904991316489	0.0164032518844207	9.7985372747136612	-0.0694197825400018	0.0306704117942035	0.0086069242926222	
+5.1189999999999998	0.0441146081383481	0.0129451029140674	9.7951689595102760	0.2148329192806349	-0.2108429716896422	0.2564964138434732	
+5.1200000000000001	0.0484195217412251	0.0438791603017878	9.7980838581818670	0.1884516412836649	-0.0852227983451998	0.1149089807069346	
+5.1209999999999996	0.0642413076920725	0.0161481551819765	9.8123634119685814	0.0917818757878104	-0.1487962234737888	-0.0941439091725833	
+5.1219999999999999	0.0644541794579144	0.0368144221249254	9.7915115454099713	0.1842111401339998	0.0442518622824332	0.1937227982365212	
+5.1230000000000002	0.0649101060634176	0.0197235775714509	9.7809507065066530	0.1434003946291794	0.0815783467280009	0.0959546465290141	
+5.1239999999999997	0.0470717924239783	0.0079881990117568	9.7913804964254929	-0.2825598478990663	-0.0478784292883266	-0.0511810951740986	
+5.1250000000000000	0.0658549136959949	0.0205384131794421	9.7846149269961789	0.1113972346203818	-0.0101691777842783	0.2161613365085845	
+5.1259999999999994	0.0690267772332031	0.0219958083689419	9.7904194288765733	0.0972204089031762	-0.1187741130251155	0.0788059037762513	
+5.1269999999999998	0.0588860058824549	0.0180517095964997	9.8049300848573999	-0.0125236683691143	0.0744753928339679	0.1819102590169756	
+5.1280000000000001	0.0545146399025641	0.0350585996558454	9.8035197710321018	0.2798034843263139	-0.1706604616352513	0.0779508712215030	
+5.1289999999999996	0.0395381803417103	0.0273538135398274	9.7678761632267843	0.0229172151654187	0.0427624705355133	0.1465647144306815	
+5.1299999999999999	0.0589388284467078	0.0217458599448237	9.7757826636105403	0.2455753828175782	0.0105370370170793	0.3655164486189536	
+5.1310000000000002	0.0800974984455743	0.0316166257915884	9.7993437621160773	0.1906672322981011	0.0504838203642566	0.1976172612914355	
+5.1319999999999997	0.0567307473982142	0.0250801607360608	9.8112731543174228	0.1447654914598872	-0.1273757008279517	-0.0505925497317144	
+5.1330000000000000	0.0686621113999547	0.0281904010655109	9.7813292410410462	-0.2276904715142522	0.1535036018690592	-0.0168725532354571	
+5.1340000000000003	0.0647759740901805	0.0195124395746703	9.7770946189932886	0.2861034900134379	-0.1592840852088503	0.0744688937494752	
+5.1349999999999998	0.0635544221939623	0.0386637006039035	9.8281944767338860	0.3312630168360557	-0.0702958700496658	-0.0018317054660756	
+5.1360000000000001	0.0691674578521120	0.0147401957917739	9.8029394373730607	-0.0471753303599107	-0.3892020528565186	0.1913480029682889	
+5.1369999999999996	0.0549959126016367	0.0361085697436986	9.7831343751162265	0.0838885795148318	-0.0415237853055990	-0.0678389793638697	
+5.1379999999999999	0.0494444449554708	0.0141214602270073	9.8002573326089397	-0.0750139460621735	-0.2704448263809033	0.0344250045927844	
+5.1390000000000002	0.0583529370342329	0.0352570054265979	9.7988413691370972	0.0825198175606335	0.0312005812120765	0.1286076588767261	
+5.1399999999999997	0.0760652452368902	0.0232061230842112	9.7950764076797654	0.1316375407328045	0.0627662960454392	0.1836147655009207	
+5.1410000000000000	0.0539936610075539	0.0306588207213058	9.8034641087859775	-0.2989191986819870	0.1329072636258301	0.2242604950698741	
+5.1419999999999995	0.0637331883186481	0.0204691507870757	9.7948798972153757	0.0178263094113140	-0.0331751522647794	0.0094257529499656	
+5.1429999999999998	0.0685621669758290	0.0213637023223498	9.7850984747623571	0.0527702599229208	-0.1744024794450359	-0.0506486689416157	
+5.1440000000000001	0.0578788281612165	0.0279749130007646	9.8045778338354879	-0.0366412723574848	-0.2728362737586365	0.0612298263007398	
+5.1449999999999996	0.0598483557567721	0.0121598731979222	9.7969871132256170	-0.1323154869801413	0.0561590103087273	0.2346670918469339	
+5.1459999999999999	0.0586156455927126	0.0299842292636373	9.7874193390215378	-0.0287002511725346	0.0619696472725678	0.1093806632716143	
+5.1470000000000002	0.0631122512906088	0.0056507848137851	9.7920743415593474	0.0210949615720199	-0.0048325629397966	0.1564847276536416	
+5.1479999999999997	0.0606805188588898	0.0101963603818676	9.8077017971842082	-0.0791597134275448	0.0020908610615382	-0.2012231805136078	
+5.1490000000000000	0.0515623046599915	0.0300697919945924	9.7964225356389338	-0.0990164756461797	0.0448847770164998	-0.1090763191455135	
+5.1500000000000004	0.0506378050765914	0.0205068401894043	9.7948239143636862	0.2852991610340609	0.0003339125892227	0.0495467262072184	
+5.1509999999999998	0.0574304739550711	0.0245533033808254	9.7942370417075839	0.0297549559003788	-0.0507616886749390	-0.0774242394520753	
+5.1520000000000001	0.0464097753785611	0.0212745037549240	9.7841839540698814	-0.1160562864680404	-0.1542931673088636	0.2371378871482574	
+5.1529999999999996	0.0483131890599705	0.0425386690131330	9.7805228913647113	-0.0239262708466471	-0.1702178045133159	0.2758386578843605	
+5.1539999999999999	0.0605774288494659	0.0149055803991093	9.7923387118323877	0.0445487619274532	0.0156019732220281	0.0412204000136739	
+5.1550000000000002	0.0657635324679424	0.0202693364852789	9.7865373783605349	-0.1930266262129524	0.1206015065913297	-0.1505113620871867	
+5.1559999999999997	0.0366130597683653	0.0177367775058948	9.8213448644333781	0.0328744416788383	0.0302172114018210	0.1875733063907463	
+5.1570000000000000	0.0325442769285207	0.0045578500295134	9.7799219916794637	0.1257688163287571	0.0957261865273922	0.3728146519783636	
+5.1579999999999995	0.0341996626607209	0.0050116837654130	9.8043679684373739	-0.1552179621910157	-0.1616808094669420	-0.0200015547953459	
+5.1589999999999998	0.0399023786995997	0.0284689130869795	9.7868103518734682	0.0491003279830480	-0.1740147248268905	-0.1514521020684502	
+5.1600000000000001	0.0751038143039201	0.0275363809209907	9.7937468227611699	0.1584590025334264	-0.0276860667393091	0.1034824875629844	
+5.1609999999999996	0.0605780948534532	0.0279965050723606	9.8078233110980086	0.0136779915353511	-0.2179650688792218	0.2231341191916736	
+5.1619999999999999	0.0629980119923652	0.0053822558784726	9.7970154803544283	0.0023944771419735	-0.0187472597581474	0.3677081654294082	
+5.1630000000000003	0.0649181833497131	0.0415691556591471	9.7759123896687790	0.0176982735635318	0.1520996775179009	0.3731882949210664	
+5.1639999999999997	0.0513636628974335	0.0379699090837160	9.8086916762578937	-0.1287276599735510	-0.2191392520351064	0.1600765966767267	
+5.1650000000000000	0.0470411312437805	0.0327515536571904	9.7922053528297823	0.0175740853964540	-0.1558089243962907	-0.0030001069766379	
+5.1660000000000004	0.0654412488333997	0.0108532157924558	9.7938087660312334	-0.1098975760110832	-0.0777312904741863	0.1448253869785668	
+5.1669999999999998	0.0332489784708037	0.0334343542760469	9.7951048320368912	-0.2052768133542868	-0.1368490182478010	0.1717507656371540	
+5.1680000000000001	0.0504141691554152	0.0257276555400899	9.7977213860579067	-0.0437005379812091	-0.0437778137907498	0.1179491654191067	
+5.1689999999999996	0.0625446887672896	0.0492073104692726	9.7742531861865665	0.0125237212531432	-0.0471188693411562	0.1552697771497372	
+5.1699999999999999	0.0682659288478743	0.0142025004062185	9.7810093075605682	0.1081818575528457	0.1794336283316508	0.0906236798080817	
+5.1710000000000003	0.0596327060515249	0.0247217414410574	9.8007207368161087	0.1321657711555360	-0.0235993229282457	0.1770669850501936	
+5.1719999999999997	0.0326356834219624	0.0221499950678268	9.7953614410641130	-0.0149057552881488	-0.1184853851372147	0.0644849922676825	
+5.1730000000000000	0.0569255627422764	0.0289285676407716	9.8257676692797791	0.1302604959800828	-0.1261879608502391	0.0528187335175030	
+5.1739999999999995	0.0725257024421834	0.0409142219465280	9.8024986884950387	0.0870461482263436	-0.0891934118094816	0.1614971428226009	
+5.1749999999999998	0.0761006519546678	0.0004030391643281	9.8200963727335395	-0.1146383876185268	0.0791191154305676	-0.1700719912082664	
+5.1760000000000002	0.0556875121275428	0.0176039002802785	9.7882992354404106	0.1068069330445875	0.0125037324982185	0.2394217091214935	
+5.1769999999999996	0.0701056848579540	-0.0030191913549045	9.7694897723506084	0.0735808529811683	0.2092347768591050	0.0844578076726743	
+5.1779999999999999	0.0469177220913023	0.0104879178091303	9.8053402995777148	-0.1951295046058709	-0.0180138192719028	0.0073537576966140	
+5.1790000000000003	0.0844643995789709	0.0315007902804662	9.7952098793619573	0.4492590934752613	-0.0314394759859818	0.3869453257496800	
+5.1799999999999997	0.0454515325428208	0.0372608721059742	9.8053740773138518	0.2377859917997223	-0.2852404357835573	-0.0494734971581219	
+5.1810000000000000	0.0553619989516330	0.0280503920402739	9.7755221100607272	-0.1455255912510640	-0.1188580024932539	0.1643534434448579	
+5.1819999999999995	0.0845820038183452	0.0331040500885440	9.7966304064318699	0.1207738325415797	-0.0827654771073812	0.0420198991304638	
+5.1829999999999998	0.0547762866953777	0.0032129246234132	9.7879000885222105	-0.1187075499972418	0.1472623384746432	0.1305281094710540	
+5.1840000000000002	0.0587622883571211	0.0513556209867624	9.7988683368771525	-0.2919790901281330	0.2148591696333048	0.0156174807539552	
+5.1849999999999996	0.0784014294765089	0.0264270110298266	9.7762314185595454	0.2784979603735863	-0.0382401226968140	0.1180065642705082	
+5.1859999999999999	0.0614692051822877	0.0464478525576375	9.7792669362831539	0.0229987069046068	-0.0461624683307778	0.1690112472987775	
+5.1869999999999994	0.0562699233340177	0.0363013986384063	9.8013335823170102	0.0167906004133082	-0.2335030632083554	0.1740987568282131	
+5.1879999999999997	0.0640548816733095	0.0161549547591174	9.7918898853080449	0.4029790989773596	-0.3355522232973972	0.0065407538600842	
+5.1890000000000001	0.0746849265382910	0.0281904486824519	9.8047074885030092	0.0495746390857288	0.1169182168746144	0.1517154022583246	
+5.1899999999999995	0.0540371106457644	0.0295457037013711	9.7979983359207807	-0.0492498131502274	0.0578838178542528	-0.0721294535138633	
+5.1909999999999998	0.0654151895184360	0.0021956287389543	9.7890392415042999	0.0201274943365436	0.1997720520609802	0.0616272950751764	
+5.1920000000000002	0.0477919382538233	0.0415439538865954	9.7961947806985226	0.0432890351805393	0.1879366007491442	0.1234992272011460	
+5.1929999999999996	0.0708899661633630	0.0234956263039265	9.7986826850658311	0.0850393482570622	0.0928492808653169	0.3096231462997271	
+5.1940000000000000	0.0514706801297914	0.0290150317685854	9.8004531165304112	0.0745465489578721	-0.2120603175355387	-0.1525530377957569	
+5.1950000000000003	0.0523041439795826	0.0186233675265444	9.7916053905253584	0.3037072169443781	0.0898871239292538	0.3208905514965806	
+5.1959999999999997	0.0336659540726877	0.0229650238935979	9.8039365737733082	0.0588767007595142	0.0041385826437712	-0.0092586810749263	
+5.1970000000000001	0.0339304403769154	0.0207037027380778	9.7933799111260917	0.0772827965367730	0.1454527722913943	0.1133517189394035	
+5.1979999999999995	0.0636219634939407	0.0089792331894578	9.8143761282414523	-0.0544610299039282	0.1287806207021283	0.1371560310213191	
+5.1989999999999998	0.0462001617521529	0.0137713023427691	9.7809727051511235	0.0719225595126480	-0.2774762715640310	-0.1767501326831736	
+5.2000000000000002	0.0812785640662648	0.0050334621037514	9.8141379475706003	-0.1051517093470652	-0.0909659797194526	0.0931193505538401	
+5.2009999999999996	0.0665992069233978	0.0155063822167243	9.8131967771785984	-0.0012488867525274	-0.0399349902889466	0.0677052136250732	
+5.2020000000000000	0.0823534995597497	0.0270562199232475	9.8061583367852485	-0.0607859543595331	-0.0618680643978083	0.2761683660577187	
+5.2029999999999994	0.0601010885501402	0.0291064010233554	9.7926146531826266	-0.0809491119316925	-0.0548531310316295	-0.0081095668749772	
+5.2039999999999997	0.0497397748094141	0.0304972387969102	9.7946184719864853	0.0844535707353988	-0.0743219113881866	0.0190161010448995	
+5.2050000000000001	0.0381995828630598	0.0047188101671637	9.7838228350590359	0.1302143537999442	-0.0963265908653366	-0.0443248883900324	
+5.2059999999999995	0.0483000375236256	0.0299703345739857	9.7956251428622263	0.0706283939219787	0.2507706226024348	-0.0284600743833285	
+5.2069999999999999	0.0867185485675692	0.0279357484236339	9.8188550824487884	0.1805306535403192	0.0411947540996726	-0.0514038054832286	
+5.2080000000000002	0.0381769287614784	0.0309885547953400	9.8042684774150946	-0.1509324106078126	0.1094158384853152	-0.0192625033732325	
+5.2089999999999996	0.0718486933389682	0.0188109809167293	9.7914061879915160	-0.0920351527389306	-0.2061926362939342	0.3631583338327797	
+5.2100000000000000	0.0625333250451959	0.0246054887970460	9.8137448240873280	0.1784999248830338	0.0536007184510271	0.1339334764060049	
+5.2110000000000003	0.0759760625787100	0.0401140210402607	9.8017707312948072	-0.0056010182659663	0.0113919778775212	-0.0285698274749253	
+5.2119999999999997	0.0520715623311787	0.0450692710599877	9.8055972429822127	0.2809948759519125	-0.0979620228577964	0.0254573540165112	
+5.2130000000000001	0.0737264520913446	0.0186727024484760	9.7853561770797874	-0.0347792041745463	-0.0806622908019583	-0.1619562169376004	
+5.2139999999999995	0.0742481487349316	0.0152738145310578	9.7938719297839629	-0.1508151816294209	0.0583502207944764	0.2002240991652481	
+5.2149999999999999	0.0589363570447821	0.0468214226020026	9.8149701195281516	-0.0223244383562190	0.0411236132609919	0.0832585857809680	
+5.2160000000000002	0.0606112655703994	0.0341810557270486	9.8044647308156545	0.1863667777444848	-0.0867901454648502	0.2214301895070931	
+5.2169999999999996	0.0551475574302609	0.0412872914751886	9.7830764635734599	-0.0362822288710689	-0.1505638874221750	0.3268210729198012	
+5.2180000000000000	0.0640495470331255	0.0175645360531140	9.7929108553190627	-0.0538481174958661	0.2052837557259632	-0.0632203119843360	
+5.2189999999999994	0.0418926932252064	0.0437796564772309	9.8134667207687638	0.1129450349989739	-0.0816861064160595	0.0013893258211824	
+5.2199999999999998	0.0543144460241859	0.0318750023002927	9.7917388375980039	-0.1945887216224563	-0.0919469414572848	-0.0787941826444581	
+5.2210000000000001	0.0837658705660535	0.0139900520895621	9.7903517139016234	0.0454848472715227	0.2334601296300631	0.2695826784628363	
+5.2219999999999995	0.0728479578509989	0.0240239245649714	9.7755419817591207	0.0015766205675326	0.1331938484669641	0.2942339405083979	
+5.2229999999999999	0.0526705563592304	0.0393192146027547	9.7967648248311718	0.0338855152981409	0.0034801221121610	0.3197719217841440	
+5.2240000000000002	0.0769964383886139	0.0163799947061853	9.7858735775006771	0.0506980922565171	-0.3416967276105837	0.1004084470832219	
+5.2249999999999996	0.0567431726212492	0.0400142196317100	9.8035430874409535	0.0342639564322311	0.0514055508838337	0.0742591421259706	
+5.2260000000000000	0.0723639316234961	0.0274967016554397	9.8055370914486968	-0.2684297344890449	-0.0807203991582913	0.0989581013899662	
+5.2270000000000003	0.0593335616682752	0.0157284228861856	9.8105732129789569	0.1400226674989340	-0.0611578975262690	0.1717383533519495	
+5.2279999999999998	0.0700995456617754	0.0136268803325030	9.8147230088168342	-0.0966079158189217	0.0696074720157851	-0.1487989733595034	
+5.2290000000000001	0.0656705680042364	-0.0007440982123823	9.7840879251200175	-0.0014046908780638	0.3241871870219082	0.1135012634405410	
+5.2299999999999995	0.0659436130388563	0.0129784567704017	9.7987408223077619	-0.0074159343368417	0.2652497289827294	-0.2372257427031390	
+5.2309999999999999	0.0592525669274278	0.0256261473797523	9.8046580649504911	0.0776334879726235	0.2499170863755605	0.3756183379473015	
+5.2320000000000002	0.0406087634069827	0.0214268310069338	9.7999492917463193	0.0000834324245734	-0.2482187714434894	0.1632625840031240	
+5.2329999999999997	0.0631554591102442	0.0384584125263612	9.8018724879628838	0.0290914250288763	0.1121066962639856	0.1637054312948254	
+5.2340000000000000	0.0714678643900685	0.0122705048136541	9.8146352278328859	0.0837531599417775	0.0708725535951675	0.0363258891508896	
+5.2349999999999994	0.0652438937297413	0.0235585826705346	9.8242357387982224	0.0598469627766049	-0.0145113667497248	0.1366946462196099	
+5.2359999999999998	0.0562117287920157	0.0398011109947252	9.7981201691558955	-0.1762168172792357	-0.0651039353382951	0.2218501793317463	
+5.2370000000000001	0.0677908561113182	0.0257589973859572	9.7915496117558494	0.0617691304358173	-0.1112255807681359	0.1451943335310495	
+5.2379999999999995	0.0748264948967579	0.0341937169532979	9.7941204380396591	0.1045748716215203	0.2288697303419946	0.3696196670947071	
+5.2389999999999999	0.0864236524170266	0.0229742154902162	9.8129528201627352	0.1223222978091819	-0.0432836757720494	-0.0016688221982397	
+5.2400000000000002	0.0634678405797067	0.0163923867260079	9.7840416223619613	0.1655300125195738	-0.1072550198310638	0.1408639931132404	
+5.2409999999999997	0.0569157295817073	0.0213134040097101	9.7957920401463685	-0.0044296273229647	-0.0052117972751690	0.1351374729535145	
+5.2420000000000000	0.0488185114730540	0.0080845869702621	9.8021525872379858	0.1359219519859861	0.0922603881015480	-0.0213281689831810	
+5.2430000000000003	0.0726000612347916	0.0319588864767694	9.8107457949258787	0.3709820028036562	0.0202524279040473	0.2465437618311219	
+5.2439999999999998	0.0852869989150832	0.0350609090354718	9.7906649048852845	-0.1091735976828766	0.1004355210964661	-0.0745640444168500	
+5.2450000000000001	0.0541407253807080	0.0153203751163110	9.8007309239535374	0.1060087803366795	0.2283646962390077	-0.0693712012535424	
+5.2459999999999996	0.0560777749270626	0.0237552695353290	9.8077099382931063	0.1262692147173604	0.1479229679618664	0.0008127077080098	
+5.2469999999999999	0.0414086082791037	0.0097209057918992	9.7979817017499826	0.1068570482479836	0.0070428132980962	-0.0986952076869186	
+5.2480000000000002	0.0555857851431681	0.0266628787646550	9.8197477249787557	0.0912658067584659	-0.0461771097171005	-0.1635141503886587	
+5.2489999999999997	0.0599864095003109	0.0348374004293511	9.8092227085495782	0.0561680589899930	-0.1731787997518747	-0.2836523402676568	
+5.2500000000000000	0.0616947817066244	0.0382983861700694	9.7885449719761990	-0.2039420157924022	-0.1487248376644534	0.0927215171867766	
+5.2509999999999994	0.0818430871789541	0.0289828445177537	9.8076703833064656	0.0590860829403529	0.1695108215418193	0.0091327990050783	
+5.2519999999999998	0.0579503250689631	0.0192329637467758	9.8063923854750605	-0.0093140540338548	0.3510177721375236	-0.1351529532742378	
+5.2530000000000001	0.0497166754412628	0.0183758771675147	9.8010962368637013	0.0548078826619380	-0.0131284031864591	0.0912114762073075	
+5.2539999999999996	0.0620725148447967	0.0075571333802731	9.7910061686606866	0.0422517966453061	-0.1867857547063099	0.2239879922595784	
+5.2549999999999999	0.0618872185424361	0.0275229015174951	9.8052982452873039	0.1158503742803390	-0.3733677002596910	0.2068911263124371	
+5.2560000000000002	0.0499092022107221	0.0308254330659236	9.8134913634650527	0.1024854010261149	-0.1619411605991596	0.0221437968699578	
+5.2569999999999997	0.0502378794944431	0.0182669376502234	9.7834793204651387	0.1087763200806032	-0.1137522133166561	0.2807935089045509	
+5.2580000000000000	0.0696427155189855	0.0263712379280402	9.8069901023405723	-0.2120675876742975	0.0552028850628613	0.1456672777188270	
+5.2590000000000003	0.0732654415118416	0.0148897376389395	9.8150694177707294	0.0823446613201016	0.1129291958150404	-0.0383627980537897	
+5.2599999999999998	0.0759373883040962	0.0208540930425399	9.8110455989136351	0.1143812179322931	0.0734779778766761	-0.0445214292574298	
+5.2610000000000001	0.0474041137898748	0.0301825288003679	9.7997684515928789	0.2883413308992137	0.1429985281987022	0.1683130982702468	
+5.2619999999999996	0.0688801618760246	0.0090779571879544	9.8069129071770416	0.0539607147545579	-0.0283200026763843	0.1682129842733341	
+5.2629999999999999	0.0793002887451458	0.0265805477470544	9.8012930065272013	-0.0259636986253787	0.2282628179224108	0.0775290101886283	
+5.2640000000000002	0.0484567752244581	0.0344393069481842	9.8027757960352258	0.0999687682168413	-0.0052632288227565	0.0541876110982637	
+5.2649999999999997	0.0418388823452542	0.0086696667989277	9.7894530224334932	0.1191708570548118	-0.0994345347147050	-0.0632122071131635	
+5.2660000000000000	0.0419180998084027	0.0248317278344880	9.8027990864886316	0.1460930424545014	-0.1154106733414813	0.0358145070890958	
+5.2669999999999995	0.0761986320249430	0.0252812793915867	9.8092361281546872	0.1887097386042105	-0.0644705229839288	0.1470178373034481	
+5.2679999999999998	0.0731116117304054	0.0201883663974332	9.8167587280464907	-0.0957964985136403	0.0632342422470369	0.0516850528928208	
+5.2690000000000001	0.0412745396141049	0.0266842070430096	9.7824714092246818	0.1208169881736116	-0.2160035916135636	0.1827134142630840	
+5.2699999999999996	0.0805875961805099	0.0287482772863200	9.7841645591474986	-0.1174996700988966	0.0570229133784866	0.1280934351711271	
+5.2709999999999999	0.0523424590661489	0.0096185555528193	9.7987199657292443	-0.1948579181088488	-0.2413643750895959	-0.1273734466089398	
+5.2720000000000002	0.0600898864796654	0.0267994464569603	9.7901820600009994	0.2075946719572987	-0.2384784901881765	0.0009887070338833	
+5.2729999999999997	0.0503667774059347	0.0315996472953744	9.7933266055700177	0.0436405904233015	0.1726955807588380	-0.0583773459357867	
+5.2740000000000000	0.0510225452071622	0.0454515099411826	9.7852414369475333	0.2770655406537814	-0.0008376447757542	0.1093958492986044	
+5.2750000000000004	0.0519211933816191	0.0251572003393517	9.7924860599234371	0.2571443468392967	-0.1010173681216057	0.1217926582256921	
+5.2759999999999998	0.0583758913299004	0.0500564824556786	9.7912345301606543	-0.1187297060811673	-0.0385219802243072	0.1129446502154073	
+5.2770000000000001	0.0418415832454363	0.0196146271253645	9.8184207125813465	-0.1746612706600137	-0.0712308294135214	0.2333819709952115	
+5.2779999999999996	0.0632709638941586	0.0254982775482437	9.8003464420840150	0.0387878430486901	-0.1911669039561702	0.3853118483406467	
+5.2789999999999999	0.0580060765610588	0.0367285497341565	9.7801009286768021	0.2145762371785614	-0.0874894376460290	0.1094394648316488	
+5.2800000000000002	0.0526779049471605	-0.0042834284198927	9.8008524976950291	0.1516024543038759	-0.0210799875899603	-0.2744453293175938	
+5.2809999999999997	0.0711450189739772	0.0096170934344889	9.7753847821043145	-0.3078215315294655	0.1381771397015232	0.0994084680126711	
+5.2820000000000000	0.0577859578927809	0.0245856992693523	9.8003958257967874	0.1016757113832451	-0.2401970351540224	0.0843289806213226	
+5.2829999999999995	0.0685574944366033	0.0431094096748218	9.7851863203022234	0.0043081292281412	-0.1560507025490845	0.0809011869476943	
+5.2839999999999998	0.0696534507242161	0.0057161156019233	9.8059071211100370	0.0131351110985402	0.0940804385032819	0.0661800063022487	
+5.2850000000000001	0.0607246863533626	0.0103275169763623	9.7867413894221276	-0.0150489397233892	-0.0635570935134201	-0.0988484928720613	
+5.2859999999999996	0.0704117170213238	0.0355614448379044	9.8001907161990136	0.0642553068209697	0.0339129705926938	-0.0688364152819274	
+5.2869999999999999	0.0650218698379018	0.0342086770510725	9.8037557341414683	0.0323456179033235	-0.1460155466078503	-0.1748724290644845	
+5.2880000000000003	0.0666904001621491	0.0482143975853781	9.8243652143410838	-0.0277778804276966	0.3306193042638348	0.1967004099485927	
+5.2889999999999997	0.0335964863521770	0.0262234837849334	9.7818886585819573	-0.2677516111968600	-0.0113940069552794	-0.0387060107094799	
+5.2900000000000000	0.0553868202145137	0.0250335012236737	9.7922988284431653	-0.0946225561567432	0.0038951334918393	-0.3018072145981451	
+5.2910000000000004	0.0640575720537159	0.0364373206476655	9.7957142943543509	0.3208327491208329	-0.0915922979808343	0.0574064176196853	
+5.2919999999999998	0.0466342964273538	0.0266250093345340	9.7961242736771421	-0.0318455509904964	0.1446357561054593	0.0792505108469314	
+5.2930000000000001	0.0404679276376998	0.0233756778867301	9.7961229677360180	0.0929896118329952	-0.0799618177384499	-0.0258501281124831	
+5.2939999999999996	0.0687311777119940	0.0359517575986496	9.8057626414069201	-0.1901304563951808	-0.1901945845978885	0.1753611042282171	
+5.2949999999999999	0.0662259386738016	0.0153150890757964	9.7906835936274863	0.0043705547512067	0.1205901137853473	0.0231844142180679	
+5.2960000000000003	0.0839638745997949	0.0295909411563094	9.8121282521258895	0.1409848397633649	-0.0539990122680524	-0.0748170230289213	
+5.2969999999999997	0.0622055957339629	0.0127994138853709	9.7970060214486683	0.1319585443062156	-0.0132010271379834	0.0185595955912495	
+5.2980000000000000	0.0582728028213223	0.0156535660444130	9.8197435573517140	-0.0234238367267016	-0.2043941704430084	0.4102377952719078	
+5.2989999999999995	0.0632427964147577	0.0312236587654288	9.7936992949795645	0.3867891226382681	-0.2412532425885216	-0.0223496096081952	
+5.2999999999999998	0.0710266956681224	0.0366317436806707	9.7897107984521003	0.0332596542121914	-0.2560592506598344	-0.0152600765928453	
+5.3010000000000002	0.0680072503837225	0.0173981315614768	9.7970419883751347	0.3263317445015768	0.1043704610995422	0.2818773694006070	
+5.3019999999999996	0.0421229934337908	0.0314664994555882	9.8080957229410721	0.0686319262572524	0.0617105713788560	0.0188358436780390	
+5.3029999999999999	0.0447074282874391	0.0106867053484230	9.8112813063705513	0.1448504044088644	0.0272955088907098	0.2563071975456045	
+5.3040000000000003	0.0625665523989464	0.0262372198000899	9.8023969211642701	-0.0117201158045794	-0.2273753616770241	0.1979497351997869	
+5.3049999999999997	0.0727531542991744	0.0049863354768846	9.7889379764617868	0.1505464801766149	-0.1921972880912232	0.3316379185714419	
+5.3060000000000000	0.0682896864446572	0.0184199526624776	9.8192527138101227	-0.1004190174883117	-0.0115632245730569	0.1359558026003272	
+5.3069999999999995	0.0583736324617419	0.0441323444758176	9.7894841146576930	0.1216101398178807	0.1576302460867580	0.3783563871461189	
+5.3079999999999998	0.0633785923942698	0.0034177006178766	9.8151030229402245	-0.0710021187579482	0.1925817785920891	0.0675869783285373	
+5.3090000000000002	0.0665997807042004	0.0260210731766103	9.7925309236415483	-0.2060303594152577	0.2052523123956551	0.3141392393721056	
+5.3099999999999996	0.0725599137692906	0.0326311042720342	9.8181381614159466	0.1775475251977255	-0.1790437719729270	0.1178092624188465	
+5.3109999999999999	0.0508866882994206	0.0349496859588836	9.7822720404382668	-0.1882123757940022	-0.1955233734153607	0.0621386933201900	
+5.3119999999999994	0.0592492836390613	0.0060519745766648	9.8104836329034590	0.1431007196498846	0.1570197245716557	0.0863683557156727	
+5.3129999999999997	0.0458660218211157	0.0101738120712784	9.7990491582915542	0.1446301767723163	0.2454660617312132	0.0225227183206801	
+5.3140000000000001	0.0436098897878249	0.0233049358843022	9.8029069730497991	-0.0045752644238217	-0.1636475511466530	0.1865524829724899	
+5.3149999999999995	0.0446565305776610	0.0198089924160305	9.7934178882663421	-0.0415550916736420	-0.0507375571683238	0.1331312838480906	
+5.3159999999999998	0.0656457470761449	0.0434750451964014	9.8026394469663476	-0.0438210797536011	0.0121251863701689	-0.0342422050514641	
+5.3170000000000002	0.0543240066622259	0.0544284647573316	9.7915085638376240	-0.3268651058988699	-0.1350102791161220	0.0112788346886810	
+5.3179999999999996	0.0565717346059641	0.0530787450144127	9.8028795478410817	0.0280020477468444	0.0627544465286190	0.1042178926608453	
+5.3190000000000000	0.0564048816526677	0.0236635467638605	9.7793843158296312	0.0411942960904947	0.0325838433473608	0.2324402249440293	
+5.3200000000000003	0.0781261830052193	0.0197852536778924	9.8104497576486445	0.4171600226777152	-0.2767240439898427	0.1438425523717724	
+5.3209999999999997	0.0684334876788405	0.0377802462412026	9.7997375891576830	0.1005610558974779	-0.1027951902330945	0.1548909393054761	
+5.3220000000000001	0.0621014302074687	0.0219448320342203	9.8059359451410000	0.2070833259696735	0.0432378669256581	-0.0911595451337623	
+5.3229999999999995	0.0801334169236591	0.0159422146421645	9.8115806384264452	0.2727873157526239	0.0554398656939031	0.3134289497359742	
+5.3239999999999998	0.0555002381067062	0.0366877468916197	9.7903306710881122	-0.1248844215223821	-0.1758038434953405	-0.1654018315074374	
+5.3250000000000002	0.0412436151715920	0.0336400056410992	9.7966626896420426	-0.0100338912874846	0.0376816121734525	-0.0585975804726670	
+5.3259999999999996	0.0552747055103071	0.0357245721785835	9.7800257947322820	-0.1256727596148128	-0.1002085848565569	0.1484927818703422	
+5.3270000000000000	0.0681576484768061	0.0131519450147727	9.7918529181970086	0.0215179382825400	-0.1175175658584046	0.1118362364455332	
+5.3279999999999994	0.0703216746267793	0.0255135389912263	9.8013773855456776	0.0448391614872761	0.0536837168714667	0.2266526915376503	
+5.3289999999999997	0.0538027171529053	0.0271808153449505	9.8018103451141450	-0.0375532011379486	0.0616082216644581	0.0131245424345895	
+5.3300000000000001	0.0697118446186135	0.0175765199617717	9.7985842261349614	0.0172734418411098	-0.0671800771970611	-0.0786800858754132	
+5.3309999999999995	0.0700487649316743	0.0388004587878652	9.8050428209446299	0.1407530163431882	-0.0953158394887458	0.1016582615466584	
+5.3319999999999999	0.0616720808906980	0.0334109660396769	9.7971589369965120	-0.2016796348321211	0.0578709506884127	0.2267027994769528	
+5.3330000000000002	0.0618967739998755	0.0131489788078314	9.7860731877251865	0.0496224222479048	-0.3498468360735244	0.2502293600524143	
+5.3339999999999996	0.0612184797198536	0.0301258423182111	9.7974159536535126	-0.0883552255966483	-0.0320713678653934	0.1063743684981784	
+5.3350000000000000	0.0564360097191831	0.0065960189478252	9.8040539281278249	0.0136244288257672	0.1386134377352099	0.1546301415777018	
+5.3360000000000003	0.0288638836801884	0.0356249568145767	9.8084034797995443	-0.0582141713918739	-0.0421223063794524	-0.0563995933388887	
+5.3369999999999997	0.0666289600279807	0.0184965937645015	9.8043091167081116	-0.0024968489584566	-0.0652690236930465	0.1265066856763296	
+5.3380000000000001	0.0619020680047532	0.0158032691919284	9.7979386813273948	-0.0418497528199953	-0.0615952075161464	0.1596560317369813	
+5.3389999999999995	0.0593168660186127	0.0208335666616962	9.8182372189434055	-0.0261588464596148	-0.0843891105809086	-0.1471018458209628	
+5.3399999999999999	0.0383443693769206	0.0196696848350165	9.8018042210435041	-0.0690414847970964	-0.2210839256415837	0.0358103851642021	
+5.3410000000000002	0.0473217475954141	0.0163097127460689	9.7991618956879183	0.0186202314477828	0.1227006303991129	0.1998757879276080	
+5.3419999999999996	0.0539628364584506	0.0321116103586858	9.7999854615656687	0.0202219463059011	-0.1610484301910985	0.1189138622183965	
+5.3430000000000000	0.0532995563153730	0.0136107214692741	9.7830753090475913	0.0813898532010302	-0.0788616887487059	0.0975418542054960	
+5.3439999999999994	0.0495159356344389	0.0369496544458421	9.8089427634304993	0.1926670055036098	0.3929452566280924	-0.0780584829101952	
+5.3449999999999998	0.0560524173052469	0.0223816826744190	9.7852766069795916	-0.0244581821859316	-0.0518523136458822	-0.0775408845546302	
+5.3460000000000001	0.0578551247894379	0.0070550793984699	9.8171517530672272	0.3274447104080434	-0.1392921626860399	0.2181664899857085	
+5.3469999999999995	0.0496103959460053	0.0359968148140319	9.8008470240999674	0.2357858400926606	-0.0490481483883169	-0.1655425838836885	
+5.3479999999999999	0.0449008035269577	0.0262243790018548	9.8116700307597817	0.0961542254728282	0.1625073865070143	0.0454209726102324	
+5.3490000000000002	0.0468801891948925	0.0151564760853400	9.7953097734775483	0.0440048976455605	-0.2122717157432753	0.2929050947168818	
+5.3499999999999996	0.0394361299364897	0.0299043851288020	9.8101796832245078	-0.0847637770413824	0.0916163291057840	-0.0228766644461635	
+5.3510000000000000	0.0487172023717826	0.0028571493937232	9.7960665900344388	-0.0438798807253191	-0.0712885780974170	0.2708646821506098	
+5.3520000000000003	0.0611040812066156	0.0361961409650549	9.7935700951202254	0.1302922353952102	0.2173505022804156	0.4195689181430408	
+5.3529999999999998	0.0471842529426469	0.0295004468913748	9.8167774869771094	-0.0105195894787225	-0.0148540770315207	0.0742874150698838	
+5.3540000000000001	0.0646324168039973	0.0124080000787650	9.7846658192208409	0.1209368812001329	-0.1487348263212777	0.3519654825309105	
+5.3549999999999995	0.0874189207162391	0.0307358872180114	9.8009228894580858	-0.0522230766311576	-0.0538021581877765	0.1133209479772822	
+5.3559999999999999	0.0670826117793551	0.0346213930970855	9.7978006676441645	0.2694866505676370	-0.0263280078406418	0.1699767847330407	
+5.3570000000000002	0.0658413762727929	0.0058988528674119	9.8053391235603407	0.1503514478685631	-0.2692378971995967	0.0371086030291329	
+5.3579999999999997	0.0583163991739117	0.0020804556229798	9.7900227550446886	0.1655169325915016	-0.0605981321363149	0.0432597363814824	
+5.3590000000000000	0.0588665799321756	0.0182665139980547	9.7837941885526121	0.0455585465131882	0.0041481929229386	-0.0154173742414102	
+5.3599999999999994	0.0521853049909191	0.0139496454948354	9.8030025560592779	0.0203441927546592	0.1306736687368417	0.0569136057759767	
+5.3609999999999998	0.0604623841182172	0.0173028344538068	9.7995602983308565	-0.2189945927496654	-0.2290154725242897	-0.0223802324866140	
+5.3620000000000001	0.0506855090664316	0.0156954283833460	9.8234776648275357	0.4850454548691080	-0.0264581399089835	0.1473256827254353	
+5.3629999999999995	0.0685869629077531	0.0116633189847187	9.7800363112825597	0.0629325499733110	0.1420286426912696	-0.0376450478368837	
+5.3639999999999999	0.0583777431971747	0.0235672413271277	9.7746111827331195	0.1608986067155429	0.2026677633453489	0.2024340768960741	
+5.3650000000000002	0.0537856013745490	0.0152752384428960	9.7995323007323378	0.0334699776668772	-0.1026819645719750	-0.0302109635433870	
+5.3659999999999997	0.0795563443206985	0.0192501918366832	9.7982810116822439	0.0997473259452601	-0.1505413957961586	0.0643772458247525	
+5.3670000000000000	0.0138918556489670	0.0314520367037965	9.7716588221304761	0.0206579713833818	-0.0403968151988353	0.0885271917234636	
+5.3680000000000003	0.0612904868257279	0.0221096728070800	9.7939753642867053	0.0506800749876719	0.0380874754309070	-0.0825835017035356	
+5.3689999999999998	0.0714290611322031	0.0313912453238861	9.8190932715950794	0.0906550146381374	0.0053096225057564	-0.0129765510272588	
+5.3700000000000001	0.0626617093909160	0.0189013008965982	9.7915269503265812	-0.0117666529844286	0.1187188716896460	-0.0141598440974179	
+5.3709999999999996	0.0615529692628225	0.0291739930363673	9.8011157302557752	-0.0771278692601828	-0.2809892676839311	0.1663441676408696	
+5.3719999999999999	0.0457993412797760	0.0239377960039471	9.8003635815291865	-0.0996836056855103	0.0622411324624160	0.0271322544898317	
+5.3730000000000002	0.0686934426247677	0.0340913754475488	9.7828344100153117	0.2798527176556926	-0.0127793799077062	0.2976895043003659	
+5.3739999999999997	0.0778456391325336	0.0241768135404906	9.8265544171343020	0.2398352842021823	-0.0525226160579690	0.2322355133359329	
+5.3750000000000000	0.0538738467773537	0.0329385413709614	9.8013959558126835	0.0085054032655713	-0.0027274098086014	0.1675329835132139	
+5.3759999999999994	0.0618024043493302	0.0085937848934761	9.7990112659333342	0.0161587862964933	-0.0730291307961986	-0.0180566556376973	
+5.3769999999999998	0.0721470151095062	0.0068471846174761	9.7885690080739973	0.0284107130635096	0.1332031435127926	0.3041465292317301	
+5.3780000000000001	0.0641594236829741	0.0171274840770763	9.8112234263026661	0.2109644478592533	0.1029671000239444	0.1474399306993550	
+5.3789999999999996	0.0506227790688410	0.0212981780208436	9.8009527546455057	-0.2028423788250830	-0.0705489944227622	0.2571709740326871	
+5.3799999999999999	0.0640956133523193	0.0344481417987261	9.7933958291664940	0.0544334911100896	-0.0379103570007039	0.0787093103764464	
+5.3810000000000002	0.0656084506627581	0.0349468695412268	9.8024305044325502	-0.0423501529615829	0.0910311286102886	-0.1089548061728080	
+5.3819999999999997	0.0642225906814414	0.0197350363215575	9.8045866342903150	-0.0740901482660762	-0.0031232721774544	-0.0571736982823024	
+5.3830000000000000	0.0666606064389239	0.0013565180226810	9.8015465188327653	-0.1030926676418092	-0.0313302282628413	0.1022064196447310	
+5.3840000000000003	0.0844160694442163	0.0209925578261415	9.8045679129444885	-0.1590399435104042	0.1507851909450750	0.0223167656067431	
+5.3849999999999998	0.0453724576138284	0.0276573218549159	9.8050348490497221	-0.0424243810519375	0.0296708248128827	-0.0027929585616834	
+5.3860000000000001	0.0704478555189236	0.0357996245900216	9.7984211675971871	0.0822937495463374	-0.0932157237964777	0.0647934526716184	
+5.3869999999999996	0.0637815667943345	0.0213466723015112	9.8129412439376047	-0.0398493490260539	0.2087875918690019	0.4505738751931195	
+5.3879999999999999	0.0590503966392069	0.0188349127385388	9.8061631107069651	0.0313230276451886	-0.2148765433041440	0.1617372775138785	
+5.3890000000000002	0.0740679789561719	0.0161593008446417	9.8068311382999447	0.1452157569725233	-0.0418324407134420	0.2375709562959716	
+5.3899999999999997	0.0555659516578616	0.0317566049098503	9.8025253756474751	0.0253781636708480	-0.0526091242033564	0.2647514146668094	
+5.3910000000000000	0.0887478525854752	0.0223128232384705	9.7879594833424370	0.3231722116642464	-0.0180916322607317	0.1133441422197249	
+5.3919999999999995	0.0762055406167715	0.0181756161590405	9.8031231466122737	-0.1264904271357676	-0.1289664392095347	0.0086688647645945	
+5.3929999999999998	0.0563214983101975	0.0219577687912269	9.7862529856468274	0.0990879386906874	0.0093162472012287	0.2994816765860462	
+5.3940000000000001	0.0624589971397701	0.0306698046033357	9.7852728705131362	0.0330382107021631	-0.1803755712876529	-0.0181830630054552	
+5.3949999999999996	0.0591291344434371	0.0189944669974471	9.7964889357030067	0.1469180286340320	0.0993445011682590	0.3464425828370482	
+5.3959999999999999	0.0595013618451211	0.0318181769742578	9.7672952789420435	0.0395498318888513	-0.0528956294892132	0.1378720846018633	
+5.3970000000000002	0.0497744954482944	0.0327654457798075	9.8073950351600612	0.1167444284562550	-0.0550224638230498	0.0384033675417880	
+5.3979999999999997	0.0439944483826463	0.0211273451921827	9.7937887563449166	-0.0835712142971145	-0.2482467889868028	0.0282562409248030	
+5.3990000000000000	0.0747870334716987	0.0326088936082225	9.8049200893254440	0.1150287973871948	-0.0670747723003519	0.3418477692954677	
+5.4000000000000004	0.0506480297845653	0.0121066093039473	9.7925962908383557	-0.1121684327329919	-0.3912290426362418	0.1937476763901849	
+5.4009999999999998	0.0597351587026935	0.0105602786195793	9.8144195243112815	-0.0462785943115433	-0.0025383460698133	0.1032599197463714	
+5.4020000000000001	0.0597852626218137	0.0275080045443809	9.7893614280048524	-0.0622149061990868	-0.2061804801291630	0.2482403197068834	
+5.4029999999999996	0.0436309231083258	0.0092236504371518	9.8038054041701894	0.0420834739901637	0.0426726240735454	0.2283013018296270	
+5.4039999999999999	0.0688247872023571	0.0290006671791138	9.7882746539334882	-0.1581583835193671	-0.1275535830345584	0.1196437586574180	
+5.4050000000000002	0.0467696113545127	0.0079481040906406	9.7821493387189431	-0.1652336921502954	0.2217804993308118	-0.0191604951723384	
+5.4059999999999997	0.0664905225287212	0.0330325351215399	9.7864290961362226	0.0265964855477789	-0.2191585913182999	-0.2644885399230084	
+5.4070000000000000	0.0540162570044303	0.0205772936031653	9.7942602106161818	0.1399405495687752	-0.2676651607176653	-0.1577244010741869	
+5.4079999999999995	0.0697311761326590	0.0308417529231619	9.7775541076064272	-0.1643176665925977	-0.0126923555815722	0.2825525420516478	
+5.4089999999999998	0.0530516851960141	0.0368735451866344	9.8173284149538560	0.2234595837085045	0.0861525751635556	-0.0135833524348020	
+5.4100000000000001	0.0487368784954456	0.0129254207296035	9.7930163638115530	0.3637189247372789	-0.1536861457231557	0.1187375374237088	
+5.4109999999999996	0.0670987388309555	0.0318543323818773	9.7835616938162051	0.1228930760629098	-0.1562916191551217	0.3009426040165547	
+5.4119999999999999	0.0546663219083684	0.0383921252541458	9.8011418944086408	-0.2213467206186657	-0.2549554198773680	0.1836234457381200	
+5.4130000000000003	0.0497187938425447	0.0179142801854885	9.7716513995502883	0.0014495388208012	-0.0442413149910915	0.2825304894598814	
+5.4139999999999997	0.0532954551946708	0.0101247898759018	9.8156196715118984	0.2406506907177616	0.0223332699780433	0.1945868459789196	
+5.4150000000000000	0.0655649212312067	0.0099678581157359	9.7995538361393688	0.0089296879734929	-0.1238645099904334	0.2275265345699617	
+5.4160000000000004	0.0556563636813608	0.0372518630102082	9.7785949464622401	0.0262797148063605	-0.2303451924398477	0.0050003020726440	
+5.4169999999999998	0.0509577866969113	0.0334322589902435	9.8134676610023170	0.1794813439008976	-0.3006194778230563	0.0913416086902580	
+5.4180000000000001	0.0553615391171154	0.0154648457182450	9.7927467803613091	0.2215045808698420	0.0389087450750648	0.3280079755152990	
+5.4189999999999996	0.0694364605324096	0.0369048920272144	9.7942490821586468	0.1490819719399699	-0.0928247015968412	-0.0404987229077357	
+5.4199999999999999	0.0663648815209308	0.0263914337102851	9.8104377630420938	-0.0543210351720977	0.0627833262989229	0.0254256563063850	
+5.4210000000000003	0.0548438132245307	0.0407751739144507	9.7771823161851792	0.2625451501542720	-0.1755086802046266	0.0040140331868110	
+5.4219999999999997	0.0745106806126868	0.0291639407174743	9.8039128204388231	0.2039245280862890	-0.0361653437162925	0.1492936496411441	
+5.4230000000000000	0.0704656557914827	0.0257206682077438	9.7970483332944500	0.1812589025579115	-0.2314323229440956	0.2231015112003819	
+5.4239999999999995	0.0380917846483076	0.0078736883090654	9.7909552405772633	0.1237571061808067	-0.1794501951430210	0.1225869626205187	
+5.4249999999999998	0.0511058463076023	0.0306244354167607	9.8003326948578806	0.1061031471678950	0.0249207559664314	-0.1137768739976970	
+5.4260000000000002	0.0553606244808475	0.0312728050992604	9.7878976162231037	0.0137100884450911	0.1008758689509978	0.0611222184551329	
+5.4269999999999996	0.0538399563270072	0.0274340246717021	9.7974711005197985	-0.0368463636408890	0.1084529118821567	0.0722280150511189	
+5.4279999999999999	0.0628264834035484	0.0256096368469118	9.7781542771266174	-0.0395285151358516	-0.2947713449610241	0.1690828698568786	
+5.4290000000000003	0.0582591484114076	0.0179696284658825	9.8136553120769516	0.2110657346603972	0.2635092849100416	-0.1857529810589665	
+5.4299999999999997	0.0655553762953447	0.0494359574602214	9.7879565321934763	0.0134275792217068	-0.2199878758124670	0.2203085726205126	
+5.4310000000000000	0.0484740572704771	0.0184107107968102	9.7942146897781708	-0.2705194291802350	-0.2106439355965506	-0.2797888851961257	
+5.4319999999999995	0.0659741383111430	0.0226790199602903	9.7917485036993241	-0.0600576021217569	-0.1772920347423061	0.1936112630220867	
+5.4329999999999998	0.0513160331890179	0.0109752240665829	9.7974779231131777	-0.0022823610720055	-0.0474013718816180	0.1234168973910208	
+5.4340000000000002	0.0584184394452650	0.0486644569081859	9.7901387935673583	0.1308537364282192	0.0674171282995876	-0.0089423430469039	
+5.4349999999999996	0.0503792529581981	0.0252928760680647	9.7973538316494651	-0.0330604637492083	-0.2201461205250898	-0.0747014834188900	
+5.4359999999999999	0.0567946202886508	0.0245133272404837	9.7966550481964632	-0.0375055057708752	-0.0306002307757173	0.1671408235843907	
+5.4369999999999994	0.0526565953273282	0.0070144712724104	9.7698995600946965	0.3361238182508903	0.1390056734698410	0.1207066262979793	
+5.4379999999999997	0.0584876528980788	0.0308300443261474	9.8088501429208694	0.2026331651959267	-0.1568681553422499	-0.1263890544895373	
+5.4390000000000001	0.0540991818113641	0.0287449194484734	9.7939931277830770	0.1991601059478943	-0.1333534765775105	0.2158409510694183	
+5.4399999999999995	0.0528285356192765	0.0267825046837685	9.7963227989550248	-0.0121075453703938	-0.0987004908175399	0.0714837171474299	
+5.4409999999999998	0.0794334701121178	0.0425724833478164	9.8080487416022866	0.0478222320229327	-0.0998804356643731	-0.1093245310030955	
+5.4420000000000002	0.0251386015874532	-0.0048382943479467	9.7969930962281957	0.0110494163272452	-0.1448717958058812	0.2786293898069834	
+5.4429999999999996	0.0661862265342758	0.0134854780275028	9.7906480232761375	-0.0764312529789012	-0.0653155737817006	0.1984467580609093	
+5.4440000000000000	0.0529941832810976	0.0173606347564259	9.7813640776984574	-0.0278236260599894	0.0358879668828825	0.3623821794043397	
+5.4450000000000003	0.0494828691176422	0.0331844704230016	9.8024020438721511	0.0513747263023830	-0.3476864776451986	0.3687501270685332	
+5.4459999999999997	0.0652437225144444	0.0292495645098916	9.7934965634691302	0.2354720805355877	0.0461466136930787	0.1148448696824519	
+5.4470000000000001	0.0639315671128202	0.0314879362669171	9.8236240559657677	-0.0260238148676707	-0.0182797151508484	0.0852733754863487	
+5.4479999999999995	0.0760105035679481	0.0365700296757560	9.7947525788416208	0.2436694288547974	-0.0867484374382616	0.2126749228872123	
+5.4489999999999998	0.0677887049545803	0.0461802932909246	9.8014278224529221	-0.2681177407526653	-0.0739044058458006	0.4346837680284521	
+5.4500000000000002	0.0682356549667441	0.0336339993222402	9.8111227003737795	0.3084204094152384	0.1036264777415985	-0.0148820580952331	
+5.4509999999999996	0.0604412942930188	0.0072819633414792	9.7791428584055566	0.0717839072956801	0.0120679970488030	-0.0930082139127458	
+5.4520000000000000	0.0549297185019360	0.0245862416598960	9.7935306346943243	0.1320186482550047	0.3445245126791565	0.0201051265225208	
+5.4529999999999994	0.0649693938656021	0.0364696414059814	9.7853836555601248	0.0663680806707499	0.0476838578405427	0.2015135852622600	
+5.4539999999999997	0.0522163283474714	0.0326689476212729	9.8059511469723954	-0.0478444531600836	0.0029225146032850	-0.1286540136850367	
+5.4550000000000001	0.0745412957313911	0.0178613151551375	9.8261746634928233	0.0148976377862810	-0.0668286135387533	-0.0281431732759681	
+5.4559999999999995	0.0527317278401204	0.0211610510182144	9.8088960905546312	-0.1298860478666782	-0.1259842181192105	-0.0905373547886374	
+5.4569999999999999	0.0755680912919600	0.0262311931281488	9.8078194163468968	-0.1561538018473583	-0.1122447336214666	0.0407313755241263	
+5.4580000000000002	0.0641373475531358	0.0302302581282604	9.8068230830561021	0.1279350113670817	0.1098737171990438	-0.0900160719571794	
+5.4589999999999996	0.0555459935626841	0.0276450132834741	9.7826728969635646	-0.2460688593060701	-0.1734423905130325	0.1604102100545864	
+5.4600000000000000	0.0664738275026270	0.0460621908646592	9.7967709263369098	-0.1041806458994764	0.1346151420872088	0.0278088561313026	
+5.4610000000000003	0.0552379639535591	0.0194347952763725	9.8098400070829737	-0.3299291522173715	-0.3054122355210522	-0.0521932843803111	
+5.4619999999999997	0.0485891593047027	0.0234794572900309	9.8106838151634008	0.3673869650574180	0.0866040579053313	0.1077046682451756	
+5.4630000000000001	0.0617635231221900	0.0375627276895412	9.8049162503372500	0.0035102960821906	-0.1808804235507044	0.0953337095152036	
+5.4639999999999995	0.0408064938616797	0.0068510212804087	9.7983632730104180	0.0008641253789567	0.0520195814460488	0.0912924480538068	
+5.4649999999999999	0.0670847699669780	0.0252741196841478	9.7928032909034552	0.0259468286497144	0.1583955918546074	-0.1650130171673799	
+5.4660000000000002	0.0367995324583631	0.0138045144857702	9.7973787033048652	0.0461911365087879	0.0731233926712549	0.1458883821001973	
+5.4669999999999996	0.0650563204023072	0.0478035696233352	9.7874664778612264	0.0361159323192468	-0.2416170161793560	0.0449677814683551	
+5.4680000000000000	0.0695544771637287	0.0196894892849289	9.7842037578070613	0.2675997055643758	-0.0235386979936948	0.4139489936907633	
+5.4689999999999994	0.0301517575714938	0.0400763551658451	9.8004392296586538	0.0503077991991436	-0.2785204463995800	0.1190113465738664	
+5.4699999999999998	0.0694411578040390	0.0337848392407151	9.7984016923755899	0.2022245409492317	-0.0660347203879990	0.1297892663693668	
+5.4710000000000001	0.0615564605376262	0.0339764013038045	9.7894821044782265	-0.0678411449093289	-0.0416412290260922	-0.0703231886623116	
+5.4719999999999995	0.0598408665937705	0.0274861077596508	9.7990321102653013	0.1460357991815158	-0.0027859283051931	-0.1757751963312066	
+5.4729999999999999	0.0515159552580181	0.0217833689276665	9.7734411610828911	-0.2818642476838283	0.0291870074021650	0.0213634054352816	
+5.4740000000000002	0.0580924973429940	0.0354344465810214	9.7959854645553825	0.0394579481353220	-0.0942809758923140	-0.2043208992035778	
+5.4749999999999996	0.0617663200333170	0.0382230406815649	9.7985715919476384	0.0809745982590752	-0.2158739767892808	-0.0778897812584285	
+5.4760000000000000	0.0628652011782027	0.0222546142324150	9.7948656247541646	-0.0706800104721369	0.2370725176651517	0.0602627119244896	
+5.4770000000000003	0.0754452051500358	0.0368733421968861	9.8131817865093858	0.3677120246561805	-0.1631011290067714	0.0903097076846447	
+5.4779999999999998	0.0488394706027433	0.0371908568350612	9.7992228924867444	-0.0024152087901758	0.0236258674871221	0.2026541523090470	
+5.4790000000000001	0.0464790147654930	0.0390517078317275	9.7902604022842787	0.3544236654178307	0.0020168299951300	0.2055562203296682	
+5.4799999999999995	0.0475525910184456	0.0202845269337284	9.8046652918829498	0.0588234902537241	-0.0677907282196099	0.1343951213733215	
+5.4809999999999999	0.0595612866867703	0.0323869891844813	9.7815921935771666	-0.0096263243639474	0.0794534329319199	0.0492726272174455	
+5.4820000000000002	0.0750219657184250	0.0276906728856501	9.7956994611154311	-0.0032323949750465	0.0486562995418814	0.2162178195127908	
+5.4829999999999997	0.0920455501203687	0.0155516811409899	9.7724114512233609	-0.1436667908116258	0.2087684061800405	-0.0833814784028931	
+5.4840000000000000	0.0586231328947163	0.0375756083385121	9.8059357263014704	0.0349721715603397	0.0205776258867514	0.1503913009309667	
+5.4849999999999994	0.0440301240242441	0.0494360023112015	9.8156291939002092	-0.0150300554901247	-0.0844119817945010	0.0785154847119671	
+5.4859999999999998	0.0518215729286249	0.0197035900016494	9.8019158584414701	-0.0473992200547233	-0.0316498627073654	0.1306702566886906	
+5.4870000000000001	0.0590329656381153	0.0047138253186556	9.7739079635754216	-0.1151011902958171	-0.1493879350904220	0.0273690579767922	
+5.4879999999999995	0.0792859120249149	0.0351757104126633	9.8026381625800720	0.0767041228804591	0.1234454938460561	0.3452426380846272	
+5.4889999999999999	0.0666771923372207	0.0165271358308354	9.8032903283575834	0.1881278086670612	0.0042692133898963	0.1348951013571196	
+5.4900000000000002	0.0673978614350284	0.0291623973164244	9.7849409076709275	-0.3405205131408748	0.0071803681343036	0.2081972342572088	
+5.4909999999999997	0.0804197928814058	0.0370797606270513	9.8023558135345947	-0.1364952593316643	0.0700418596296676	0.3529509884877159	
+5.4920000000000000	0.0606160354974238	0.0248080063733525	9.8012264550679387	0.0127082605260279	-0.0885074995291683	-0.3533835092015989	
+5.4930000000000003	0.0405781953144643	0.0468926865832446	9.7722949856813521	0.0657011984490914	0.0650373347353751	-0.0512903375302519	
+5.4939999999999998	0.0462603620804823	0.0081308675030102	9.7841052962105444	0.1335456328221529	-0.0366664455203594	0.1076996476942865	
+5.4950000000000001	0.0621468461004465	0.0467595462103722	9.7838444885625542	-0.0213490093152516	-0.0123960272482391	0.3641820811917436	
+5.4959999999999996	0.0512064895830866	0.0393701556786346	9.8065942833619069	0.2492309873658112	-0.0021782143077275	0.0187252614320055	
+5.4969999999999999	0.0507194695508329	0.0406832582425657	9.7920553481929904	0.0993734463248977	-0.0836339851038480	0.2127639452225514	
+5.4980000000000002	0.0679553491613034	0.0122566572386615	9.8047385131727562	-0.3879120300601886	-0.1157600991172528	0.2475549683829872	
+5.4989999999999997	0.0595820052140907	0.0156462412048667	9.8140858369038479	-0.0298224323255028	-0.1850778005994696	0.1379509699838619	
+5.5000000000000000	0.0547823105425892	0.0234895955803208	9.8014957035667862	-0.0084246633107757	0.0184209618288094	0.1808335030227897	
+5.5009999999999994	0.0720692142902241	0.0198344856618842	9.7854132829016258	0.0852821408711074	-0.1661160269099905	0.1960967614922448	
+5.5019999999999998	0.0819397748216958	0.0275328938338987	9.7978690893141334	-0.2509905313694420	-0.1346119393497235	0.0796033985381357	
+5.5030000000000001	0.0511903663565133	0.0137806527429517	9.7810092071419099	-0.0999007641401021	-0.2431272773225621	0.1707037480781070	
+5.5039999999999996	0.0538048910340414	0.0126010075953290	9.8174553250665575	0.1958202789326299	0.2004669451159413	0.3363359491756605	
+5.5049999999999999	0.0472213503760289	0.0132312446126618	9.8002383605132817	-0.0243854888230786	0.1213200735061177	-0.1071246641276057	
+5.5060000000000002	0.0603461005327385	0.0085438057338629	9.8034998309026822	0.0544131927133256	-0.2052237162053215	-0.0124174091832798	
+5.5069999999999997	0.0665369927990342	0.0002445104521277	9.7729456559470886	0.1666050028201893	0.2183680096589795	0.0336260387796139	
+5.5080000000000000	0.0573636448591642	0.0165741950533353	9.7932443852394560	-0.0994141198323831	-0.1217213715895938	0.0521843516204531	
+5.5090000000000003	0.0728130062280239	0.0192936289782650	9.8017934341653401	0.2656184989697394	-0.0548377369893949	0.0371685158412417	
+5.5099999999999998	0.0438726238686678	0.0364020844174465	9.7840917206298652	-0.0950806340587318	-0.2179447992500861	0.1176992511375468	
+5.5110000000000001	0.0687224843539216	0.0223468551698398	9.8087289026646545	0.0705460928712641	0.1067266700356667	0.0634601569461518	
+5.5119999999999996	0.0381915498558208	0.0275825641937140	9.8164456859121234	0.1946689066681634	-0.2756583276861787	0.1052151121323796	
+5.5129999999999999	0.0635204677143404	0.0379662891543611	9.7971038068436069	-0.0154541134790812	-0.0566036580480684	0.2163620924060368	
+5.5140000000000002	0.0613233222760231	0.0362738310109291	9.8034997432906295	-0.0516873949391067	0.0460838377281909	0.1382962759243836	
+5.5149999999999997	0.0631149052219509	0.0269700932074085	9.7706939920742197	-0.1624154123298447	-0.1384820408897798	0.2405037610828258	
+5.5160000000000000	0.0592400558953525	0.0415901970221658	9.7980263379826287	0.1921694275618881	-0.0653802609821347	-0.1104810308773290	
+5.5169999999999995	0.0612079742999199	0.0271327359021021	9.7901380768679971	0.2037756763198841	-0.0281474761140303	0.2614386056432215	
+5.5179999999999998	0.0440358311719612	0.0367630885418526	9.8026663428950958	-0.1391215114217701	0.0450727366721549	0.0949208248366698	
+5.5190000000000001	0.0823178272299165	0.0096018632465168	9.7851032129510447	-0.0442470949320192	0.1727333258779538	0.3098428731250672	
+5.5199999999999996	0.0611141527347776	0.0115288984248542	9.8021637177720553	0.1137403122194260	-0.0607647273855678	0.0861396044215525	
+5.5209999999999999	0.0435515999216464	0.0185726447441152	9.8022812750197961	0.2672687675660419	0.0553069417629769	0.0933896183121353	
+5.5220000000000002	0.0628989414727694	0.0148473731613577	9.7727389085430385	-0.0821602325396853	0.0284028651056291	0.0484913700211997	
+5.5229999999999997	0.0486639140550261	0.0250026235323257	9.7973836875833502	0.2909399229272514	-0.0300014472545105	0.0135521988737674	
+5.5240000000000000	0.0489528346749129	0.0195460216685503	9.7699464553083608	0.1223825862790678	-0.2249723734715455	0.0058534986840561	
+5.5250000000000004	0.0501150817268120	0.0189019422820904	9.7729617310342363	0.0474399817809756	-0.0068001436663616	0.0790169240186707	
+5.5259999999999998	0.0679457023881095	0.0255321957943832	9.7978008577354885	0.2869526625056225	-0.3773798269024906	0.1288696871279517	
+5.5270000000000001	0.0672427425192399	0.0211610492676815	9.8139341402820310	0.0833645413587407	0.1585128872179880	-0.0391235315357304	
+5.5279999999999996	0.0838145101636056	0.0345030080316459	9.7780819931769827	0.2535711747686467	-0.0680279043274447	0.1480069411804022	
+5.5289999999999999	0.0660065698435755	0.0236585303777717	9.8033359144687289	0.2007001639659682	-0.0366105143827637	0.4817103258258517	
+5.5300000000000002	0.0750824687032463	0.0346855949874959	9.7890539239200400	-0.1024059102380377	-0.2868565925024240	0.1001847795404092	
+5.5309999999999997	0.0492435749069425	0.0179201896004476	9.7954216576037716	-0.0413066860387719	-0.3203514372909258	0.2004745001099061	
+5.5320000000000000	0.0777043917855695	0.0318744439987070	9.7891150145041497	0.3844451692246253	0.0172446784932416	0.1309291202435602	
+5.5329999999999995	0.0504055907610782	0.0227788489098337	9.8093439515960146	-0.0078841644463331	-0.0926482916570213	-0.1329964271953777	
+5.5339999999999998	0.0487345333173924	0.0275088482870378	9.7931154453668761	0.0373384494512073	-0.3637705581573806	-0.0691700410565014	
+5.5350000000000001	0.0625168406796185	0.0318901805465658	9.8048376898891032	0.1593466366912797	-0.0217319463420521	0.4654257092695100	
+5.5359999999999996	0.0599271930702151	0.0426835662587449	9.8070257726744323	0.1135123828489448	-0.2198647079756359	0.1260103270750373	
+5.5369999999999999	0.0647074165908227	0.0368082407019404	9.8030302659097490	0.0843086757394747	0.1452887152375344	0.0477635331237921	
+5.5380000000000003	0.0574503046016824	0.0210284997442948	9.8053550752768714	0.0091276526970428	-0.0728343588148800	0.2479072715737459	
+5.5389999999999997	0.0824718707064172	0.0484059421677040	9.8025582104419620	0.2431142109047580	-0.1662147983134757	0.2899744731623077	
+5.5400000000000000	0.0598716900816463	0.0465713239874413	9.8111020727684455	0.2843461078653413	-0.0480096995394085	0.2381216629785864	
+5.5409999999999995	0.0697795793609726	0.0181934294839384	9.8235840929871525	0.0653606048144373	-0.0739046073545093	0.1077604905649362	
+5.5419999999999998	0.0580907394799908	0.0398650869551457	9.7715560963132049	0.0297771686509075	0.1731638518311767	0.0980052442584275	
+5.5430000000000001	0.0631781999332149	0.0096185565947128	9.7996234720113122	0.1046615711603066	-0.0599962862294517	0.2000127891852843	
+5.5439999999999996	0.0794760710263161	0.0263222750890280	9.7858974463477679	0.1801265503004172	-0.0286770745366224	-0.1547790192858299	
+5.5449999999999999	0.0767152638189286	0.0323041823357495	9.7919001824449623	0.1433277119265618	0.1387448136288537	-0.2665151572762069	
+5.5460000000000003	0.0502950056315094	0.0284389181094509	9.7982163173807511	0.1353880120339025	0.1767003793744947	-0.0389701443192656	
+5.5469999999999997	0.0504299777384257	0.0419539471256853	9.7846251154578603	0.0380731433708405	-0.0100390386084730	-0.0358752932493442	
+5.5480000000000000	0.0732315235075914	0.0450876897494195	9.7944214366743392	0.0108969381359894	0.0216734702726012	0.2985871957526619	
+5.5489999999999995	0.0588371069848898	0.0449055475492654	9.7735299374372033	0.4476029746117565	0.0304749788677826	0.1419125012677060	
+5.5499999999999998	0.0483072314027121	0.0334414450115778	9.7872009358766388	0.2145541145873706	-0.0757629193763371	-0.0493052844353146	
+5.5510000000000002	0.0674743988658316	0.0159123981008038	9.8052791121022693	-0.2476362757419692	-0.0801233725194743	-0.1101493673027283	
+5.5519999999999996	0.0509511046190401	0.0107958289545498	9.8024699477234378	-0.0025050043546211	-0.1399744287873602	-0.0522642212337631	
+5.5529999999999999	0.0476603673817927	0.0095609487771937	9.8106688800010833	-0.0978444879710069	0.1300095475230665	0.2004867875397945	
+5.5540000000000003	0.0538671769376945	0.0141753320125163	9.7720256986377194	0.1905378057426916	0.0508738869664882	-0.1074723754451490	
+5.5549999999999997	0.0549723793427050	0.0276466007598276	9.7970916782696520	0.1532142320186673	0.0756750957909123	0.0781422399771558	
+5.5560000000000000	0.0629295798106430	0.0217414424367069	9.8131441546252365	-0.1118493650970426	0.1089893432766341	-0.2271761968317818	
+5.5569999999999995	0.0456513727103479	0.0196282523577737	9.7960700054095877	0.1869813179218817	0.1243455134539802	-0.0661910064776475	
+5.5579999999999998	0.0440871939976528	0.0250059023330739	9.7944882170188734	0.1370899359923214	-0.1240590714643994	0.2654695583898937	
+5.5590000000000002	0.0553570164693791	0.0325818746686588	9.7932890036429150	0.0650908275969516	0.2985199898492066	0.4227875814459858	
+5.5599999999999996	0.0523609213711889	0.0021718381839052	9.7896971425767809	0.0772584765757464	-0.1691085025611986	-0.0577724222537624	
+5.5609999999999999	0.0576582373656117	0.0347474087006030	9.8019155866567989	0.0500452015505959	-0.0376727864483431	0.0731005949876131	
+5.5620000000000003	0.0702286276752022	0.0345658581710911	9.7787635630914895	-0.1629153293996426	0.0356925619511357	-0.0888661532474665	
+5.5629999999999997	0.0466182387608634	-0.0002843587801320	9.8089247339815557	0.0591968841618945	0.0077238943215245	0.0389164431365294	
+5.5640000000000001	0.0330974098037801	0.0033856399051455	9.7910597455263311	0.3217685049432557	0.0941898035044955	0.0294640823341120	
+5.5649999999999995	0.0410871049233334	0.0091488621647287	9.7935539017317268	-0.0530232893272171	0.2260387442224423	0.1175260570639161	
+5.5659999999999998	0.0686824052072400	0.0307523203256116	9.7838757794020026	-0.2151723849568673	0.1691682796043622	0.2171033018084013	
+5.5670000000000002	0.0647445944173310	0.0129493334683337	9.7953683750559701	0.0843499829428198	-0.0478438453531920	0.1777965133465959	
+5.5679999999999996	0.0799661822676011	-0.0043233050857081	9.7924819788775821	0.0614318932655167	-0.2681247453855600	-0.1179476306338167	
+5.5690000000000000	0.0519916877320305	0.0362336612817428	9.7919522544877484	0.1219563890977256	-0.0706304398564013	0.0972008836989433	
+5.5700000000000003	0.0678366775213323	0.0316376158111456	9.8235665927302875	-0.0230286922570231	0.1027204844759569	-0.0276927281609675	
+5.5709999999999997	0.0460986339464285	0.0339817653238258	9.7840860090110393	0.1109115733387876	-0.2197816204496944	0.0192364344196589	
+5.5720000000000001	0.0700679371559541	0.0178047679412544	9.7771371766456578	0.2130934665834921	0.0401810187643814	0.0408483722623478	
+5.5729999999999995	0.0597354653899360	0.0166596005553228	9.7900316625172685	0.0154999198541030	-0.1459530159098044	-0.2373918820016886	
+5.5739999999999998	0.0553379245488701	0.0156081285444458	9.8231021440808490	0.1661953066111629	-0.0732046630795240	0.2742201703528216	
+5.5750000000000002	0.0791725447344096	0.0384865091283165	9.7858605048869389	-0.3006432579986146	0.0271732845379972	0.1652116528670519	
+5.5759999999999996	0.0751921697796370	0.0419368815056912	9.8078666350218846	0.0004642184277491	0.2311763678317688	0.2774451394697028	
+5.5770000000000000	0.0835329745429841	0.0444723259039944	9.7904191978125379	0.1038359747383983	-0.1740692842637923	0.2481986406726872	
+5.5780000000000003	0.0769765917577288	0.0176294509608398	9.7712552937014809	0.0686874159377187	0.0684897889774988	-0.1739921107576903	
+5.5789999999999997	0.0630167738631170	0.0368830223967329	9.7978129768065916	-0.0004222687197647	-0.1574990394715657	0.2905413312823923	
+5.5800000000000001	0.0640725534205669	0.0199879515145145	9.7865515779304069	-0.2579207258900065	-0.0987111555914898	0.1879832223039503	
+5.5809999999999995	0.0436861888949282	0.0169071615699462	9.8206544389991777	0.0681592690222692	-0.0810602797653862	-0.0249700427907105	
+5.5819999999999999	0.0596689469837472	0.0395602263017332	9.7832599477426285	0.3113258710941464	0.1026280660081308	0.0988664879813700	
+5.5830000000000002	0.0588143135815748	0.0215805805655187	9.7876514280500633	0.0944779448810177	-0.0385592358492342	0.0005449093870128	
+5.5839999999999996	0.0563963243321334	0.0415514457409381	9.7927930704901609	-0.1848384308936892	0.0813208984164792	0.0772655578328954	
+5.5850000000000000	0.0476843433099217	0.0315586889964410	9.8119567891830517	-0.1982683967350144	-0.0927646311358935	0.3133042397863287	
+5.5860000000000003	0.0624279003914067	0.0369620074256952	9.8114166400717888	0.3608332417292547	-0.0162656353893423	0.0458519670398255	
+5.5869999999999997	0.0556640447135310	0.0327392128797574	9.7855807111340045	-0.1946510789215279	0.0821728314926404	0.1637935697627380	
+5.5880000000000001	0.0417097757137387	0.0448733844969193	9.7832031121118828	0.1681125284782054	-0.1120630986385741	0.0122675848882082	
+5.5889999999999995	0.0459997938540373	0.0206442143301591	9.7909778638378189	0.0298637906014559	0.1716205425726271	0.2756566754157810	
+5.5899999999999999	0.0523026774007178	0.0149626866897035	9.8020344625811191	-0.1268264450918893	0.1269148208600445	0.3212834940078728	
+5.5910000000000002	0.0796601867467072	0.0222803916224259	9.8107402148866090	0.3377440499476908	-0.3609576265414221	0.1936227418327022	
+5.5919999999999996	0.0787008487653777	0.0474367952937695	9.7947417844216265	0.0195165586556159	0.0019823555933143	0.1892140614694247	
+5.5930000000000000	0.0459900682968474	0.0195664471005857	9.7888987867699928	0.1037024209894311	0.2924397050167392	0.3128959384816442	
+5.5939999999999994	0.0551111458780148	0.0119036503790117	9.7961292080634532	0.0558166370465073	-0.1190715601398172	0.0928884557814177	
+5.5949999999999998	0.0714380101870239	0.0395313739020906	9.8104843651303355	0.0017183896357916	0.0022110786164998	0.1280670392905089	
+5.5960000000000001	0.0565371813019515	0.0253844239683001	9.8078842153935835	0.0549632933418954	-0.0485313116830001	0.1420855377898223	
+5.5969999999999995	0.0645071444188915	0.0416592742971984	9.7954023785600270	-0.1409870406183356	-0.0406881092376501	0.2183291164698836	
+5.5979999999999999	0.0766769566139943	0.0130512144572062	9.7869116887614176	0.1551138747490598	-0.0205281745749679	0.1658105686290008	
+5.5990000000000002	0.0476655928581990	0.0181825989868200	9.8160761905100866	0.2363667817711061	-0.0718368870014064	0.0230622832971783	
+5.5999999999999996	0.0716554268282941	0.0176964650868172	9.7979787487958934	-0.1294723917584609	0.2245679591183299	-0.0190373603493338	
+5.6010000000000000	0.0691661643492023	0.0256078647846735	9.8014525966208286	0.0450850991214213	0.0679678389789906	-0.1055202196205752	
+5.6020000000000003	0.0766913434694635	0.0225169251799688	9.7936253863503140	0.2497477058104453	-0.2147373059099952	-0.0356704567010285	
+5.6029999999999998	0.0637654284089338	0.0172355698216840	9.8191060707599576	0.0713969580959340	0.0794880242425352	0.0459093055122069	
+5.6040000000000001	0.0747782676095999	0.0343229758096490	9.7951363838581909	0.0607808895993374	-0.0768069172086913	0.0091129571577652	
+5.6049999999999995	0.0440671008745355	0.0520377516318199	9.7982830242410621	0.0031686325805153	-0.1577560999135063	0.2328010011705697	
+5.6059999999999999	0.0655850472280411	0.0312413244766734	9.7792510169225331	0.1686536955740793	0.0455543716431339	-0.1108637398583543	
+5.6070000000000002	0.0689038002568830	0.0192446782572920	9.7857009186700576	0.1121351091432040	-0.0986814143867626	-0.2356285544785751	
+5.6079999999999997	0.0621477204036710	0.0122369318572098	9.7958418722528009	0.1771071332918695	0.0276155467548062	-0.2276053894546883	
+5.6090000000000000	0.0372693785586608	0.0365534506229932	9.7981166785970153	0.1223866387481501	0.3375666317298186	0.1529106278191688	
+5.6099999999999994	0.0490837309288448	0.0166954829027047	9.7935881218726948	0.2346221625878158	-0.0993599472421010	0.0973107889427694	
+5.6109999999999998	0.0494024571775983	0.0389035782878732	9.7937326209225439	0.1226315096799540	0.1262015245930594	0.1836550580891093	
+5.6120000000000001	0.0564680686728253	0.0189005540904098	9.8080273476675757	-0.1295703263401130	-0.0272354116886833	0.0414201849942352	
+5.6129999999999995	0.0770505521858547	0.0344198504354292	9.8001089802708066	-0.0620626456251142	-0.0904900716607794	-0.0591690689028732	
+5.6139999999999999	0.0657237002525341	0.0414766992449419	9.7780239951569090	0.0139887473647189	0.0143146098952658	-0.0104428235739955	
+5.6150000000000002	0.0480569264797579	0.0216463448069708	9.8012599493387693	-0.0683327596456261	-0.0247486602174296	0.1818582940770530	
+5.6159999999999997	0.0550885025969154	0.0358868946485817	9.8033940728764950	0.1491763903569646	-0.0773986746453572	0.2482622780219527	
+5.6170000000000000	0.0844671844510272	0.0235703332102612	9.7880221600210362	-0.1197752785675640	-0.1293626666649822	0.2409507037122665	
+5.6180000000000003	0.0677996863181760	0.0178421841325854	9.8055807231461607	0.0102626766913720	0.1263279699765373	-0.0312118866415267	
+5.6189999999999998	0.0744051482657418	0.0327950276388386	9.8032697682023304	0.3383000446114549	-0.0970739461293039	0.2023962660654958	
+5.6200000000000001	0.0584087346367229	0.0273957409346834	9.7891731064352712	-0.0348242699649854	-0.0768852599506632	-0.0511247884060363	
+5.6209999999999996	0.0546351483744944	0.0322794178321932	9.7929134017508783	-0.0144385672980423	-0.2078234998086073	0.0034349541331721	
+5.6219999999999999	0.0386962079724905	0.0057718880262816	9.8224061908361548	0.2304048429248647	-0.1063613993781653	0.1762672200083993	
+5.6230000000000002	0.0521175505956202	0.0040461295261471	9.7815149986628604	-0.1394860836864198	-0.0636513241331544	-0.1326286083725273	
+5.6239999999999997	0.0807698457739065	0.0252364265810619	9.7868452969076145	-0.0888524489339527	-0.1092209384718182	0.1415026861288620	
+5.6250000000000000	0.0644089972066620	0.0198380173867056	9.7901757273344536	0.1811302573301110	0.0136905629469945	0.3220017566263309	
+5.6259999999999994	0.0616641625586371	0.0310713724807341	9.7972636056502207	-0.1029765607170799	-0.1972873442988019	0.2695261595930609	
+5.6269999999999998	0.0578117143915331	0.0136336268732365	9.8014419209369414	-0.0539777682774434	-0.0771525725599272	-0.1109803046211367	
+5.6280000000000001	0.0469872944098261	0.0299870935303634	9.7858863427338623	-0.0038298293191418	0.0611320445743664	0.2521042069074489	
+5.6289999999999996	0.0615024790164257	0.0222089796953074	9.8016600953278754	-0.1267668706305938	0.0020762463924902	0.1727009449918611	
+5.6299999999999999	0.0804215284392525	0.0478866725652111	9.8096081133142796	-0.2803001093220217	-0.0589161643397867	-0.0950618235705056	
+5.6310000000000002	0.0427042705945249	0.0694583418309498	9.8002158170470537	-0.0097627956790989	0.1594832307074955	-0.0858083748465757	
+5.6319999999999997	0.0569515270658996	0.0306081926805472	9.8123457828194987	0.0367640602875623	0.3920396158574766	0.0087948139489515	
+5.6330000000000000	0.0722469107584345	0.0039315372991684	9.7828166429354066	-0.2418222067307479	-0.1195353684255735	-0.1075507854098271	
+5.6340000000000003	0.0565599168859603	0.0101173170952060	9.8164458545895066	0.5369210315457590	-0.2485619831032684	0.1058280554659726	
+5.6349999999999998	0.0492557655342834	0.0102839081277308	9.7697860930369487	0.0435287247070197	0.0030644489123110	0.0218234778268307	
+5.6360000000000001	0.0561269466798942	0.0231962258672819	9.7903298403447927	0.0972992724316464	-0.1148334203320713	0.1236656889298265	
+5.6369999999999996	0.0403473956549078	0.0173462089978384	9.8136592957624718	-0.1070075843981830	0.2581881802929850	0.2080127839970914	
+5.6379999999999999	0.0522345206790552	0.0151496969541766	9.8106981072902748	-0.1858268424344631	-0.2232979311275344	0.1837028667736336	
+5.6390000000000002	0.0508335044564680	0.0161404025418125	9.8144971240629850	0.2915610660522603	-0.1928090743117273	0.0097138247943917	
+5.6399999999999997	0.0882237655067114	0.0268579052210378	9.7906621281062538	0.0571614746371267	0.1668420504740752	0.2390710415759683	
+5.6410000000000000	0.0527203825143453	0.0407949369224584	9.8145972383007027	0.1971675114186637	-0.2005699349946036	0.3259839432697001	
+5.6419999999999995	0.0554750926929816	0.0098140144404252	9.7841090578561243	0.3146561985948255	-0.1618541843428087	-0.1021838584226544	
+5.6429999999999998	0.0663473638001255	0.0611587759591436	9.8141841312550540	0.0465388913274927	-0.0404487253620776	0.2256876659047976	
+5.6440000000000001	0.0630827621472234	0.0152251447332772	9.7885282117010082	-0.0410877758375637	0.0844984107871292	-0.0160332971161587	
+5.6449999999999996	0.0501338128062524	0.0152206295655639	9.7817170512891298	0.1815146202849263	-0.0491353338583557	0.0593425680383091	
+5.6459999999999999	0.0815026411086927	0.0452270414323293	9.8260194547113855	-0.0620219651596638	0.2459884335574889	0.1314453129748303	
+5.6470000000000002	0.0538790021773418	0.0174366816829270	9.7919990824027732	0.2419769105975275	-0.2421074373950398	0.3205140010457580	
+5.6479999999999997	0.0454607902531731	0.0009000784410894	9.8042145952101141	0.2143876101139879	-0.1619377164664969	0.1039929516263354	
+5.6490000000000000	0.0423339454790462	0.0236623964065081	9.8081235501472133	0.3620502070641531	-0.0802678246409819	-0.0503108721373911	
+5.6500000000000004	0.0726157300667047	0.0056253045002693	9.7928603146915076	0.0721102769738128	-0.0548746774713648	0.1066351153814632	
+5.6509999999999998	0.0643181949890564	0.0212620241950495	9.7833153096110763	-0.1978488897148017	-0.0771085778131298	0.1212394132519465	
+5.6520000000000001	0.0480287236239638	0.0222100150057489	9.7881958373671907	0.0940713658095504	0.1112788427164103	0.2143166816007667	
+5.6529999999999996	0.0765014880669991	0.0401287458603149	9.8175155187167640	0.2817369918053768	0.1965236826012334	-0.0134525121888484	
+5.6539999999999999	0.0627321412712351	0.0252797250946520	9.7920588846010048	0.0082774296946068	0.0673376930958031	0.1034260618744719	
+5.6550000000000002	0.0533204694159416	0.0171486917552650	9.7998538280338021	-0.0621132778042782	-0.1014968448568401	-0.1048355451582531	
+5.6559999999999997	0.0328741476934602	0.0106383499015346	9.7866619450427592	0.0999648254164070	0.0433553623426031	0.0945998975545878	
+5.6570000000000000	0.0453643962584153	0.0442436875574555	9.7850025795801177	0.1103286786777561	0.2380418110319721	0.0443035457596022	
+5.6579999999999995	0.0743364533641779	0.0280705241048729	9.7787515984193210	-0.1836532438572450	-0.2483567480759032	-0.0299796370370406	
+5.6589999999999998	0.0556495118532924	0.0195966841375833	9.7889683613101628	0.0481787626572917	0.0827079915245479	0.4439731056153337	
+5.6600000000000001	0.0721345875802713	0.0359121843419015	9.8024594390579107	-0.0486817589829611	-0.0863009485362285	0.1030669819114254	
+5.6609999999999996	0.0794880138956311	0.0324211987861453	9.8174577321765231	-0.0402893741144909	0.0556216372347778	0.0327732843507335	
+5.6619999999999999	0.0729759799242907	0.0095108201339777	9.7880383617964934	-0.0449619875107243	-0.0272321707422906	0.0002937264364387	
+5.6630000000000003	0.0669182903069608	-0.0026898159290655	9.7871204911464211	0.1146213663997992	-0.0937348172754712	-0.0544377681269781	
+5.6639999999999997	0.0661095540043515	0.0177736647180014	9.7850965030001973	0.3605096220090209	-0.0616416671681572	-0.1284915926162101	
+5.6650000000000000	0.0361954753938665	0.0217755367359112	9.7939294893321804	0.0433649073223993	-0.1328215875134489	-0.0498056717224524	
+5.6659999999999995	0.0488771264074728	0.0354979255261761	9.8135694658993859	0.2292472411318850	-0.0468247596495735	0.3582089107147798	
+5.6669999999999998	0.0509829999848481	0.0333519369955028	9.7904772608881530	-0.0384330667725868	-0.0998860781917322	0.4895841115906459	
+5.6680000000000001	0.0741426302092183	0.0335033691420688	9.7964508077125618	0.0605640967893574	0.0358567669379914	0.0341016740196062	
+5.6689999999999996	0.0542498912833007	0.0574250498149748	9.7919379497985304	0.3379066203729495	-0.0070200818960321	-0.0338336877351462	
+5.6699999999999999	0.0360596105325701	0.0085687727742144	9.8162628884837400	0.0082981539903210	0.0391282635583492	0.0534909499784596	
+5.6710000000000003	0.0684656343302158	0.0203637678787929	9.7918055032787361	-0.0447942451367201	-0.1064024318332316	0.0409473199001510	
+5.6719999999999997	0.0754570431255798	0.0440992266176676	9.8052010703291437	-0.0331027284197066	0.0473122741887318	0.1154420386388877	
+5.6730000000000000	0.0767923595811934	0.0467514903453376	9.7987340038995345	0.3069961961946089	0.1388668057564241	-0.1194602142864324	
+5.6739999999999995	0.0561195852966592	0.0431438052814181	9.7957247196431663	-0.1625373074193906	0.1923633542029592	0.0529862083357091	
+5.6749999999999998	0.0717731457574769	0.0197642749321925	9.8189951795071728	0.2478429657071828	-0.1820599814123003	-0.0033423060372660	
+5.6760000000000002	0.0551561328944918	0.0351838504281890	9.7999468328457198	0.1586972296960037	-0.0788987992056538	0.1408676816223297	
+5.6769999999999996	0.0664127376593101	0.0132205720621363	9.7943452584925303	-0.0793276312444307	0.0238497881621611	-0.1965210961554757	
+5.6779999999999999	0.0500682721527908	0.0195675300462654	9.7931781434073226	0.0558128230110307	0.0269219458579756	0.0493906190719725	
+5.6790000000000003	0.0738615578882883	0.0345118084764274	9.7842576314570113	0.1211290059191335	0.0079332812382913	0.0611384512416981	
+5.6799999999999997	0.0607267124241742	0.0292090222154775	9.8082836986179132	0.1096172130584852	-0.1313257949634091	0.2269546780861926	
+5.6810000000000000	0.0663648400964959	0.0378320122728593	9.8065791579684269	-0.0560197714870666	-0.2355287840736465	0.2328694695069830	
+5.6819999999999995	0.0480328753165782	0.0166162604222812	9.8008381585945514	-0.2457931076717896	0.0126617239768437	0.1454706701863214	
+5.6829999999999998	0.0756255829973927	0.0041168340087191	9.7878979126192132	0.1146711357419360	-0.0755447371451968	0.3457062720915881	
+5.6840000000000002	0.0508773338512204	0.0217871809521121	9.7967274484465090	-0.0633673259114869	0.1578501726260707	-0.0857240486848634	
+5.6849999999999996	0.0710047749163984	0.0230499836855167	9.8092669221941069	0.1162116805895873	0.2320123323807834	-0.1712103787410972	
+5.6859999999999999	0.0694830871953217	0.0392260973245996	9.7865462965432588	0.1017284962543986	-0.1602732442422315	0.0179292001229940	
+5.6870000000000003	0.0755190294545109	0.0317297366917653	9.7953788273198796	0.3796370905521092	-0.0867091922408348	0.1912788546302878	
+5.6879999999999997	0.0591000792928278	0.0214300786855637	9.7777948150278657	0.0837864360917245	0.0603274923684301	0.0554798534779402	
+5.6890000000000001	0.0506704420011275	0.0244740930566540	9.8074010056851950	0.3503230526975000	0.0632958086127101	-0.0649889027951356	
+5.6899999999999995	0.0773544295252900	0.0442956060583069	9.7925865070179370	0.2173830813780299	-0.2698520149704534	0.0488711597227971	
+5.6909999999999998	0.0309145514349850	0.0304691474321516	9.8095921567909521	0.0376176950800158	-0.2472117682084438	-0.0538191413592996	
+5.6920000000000002	0.0633829891556169	0.0251596795210974	9.7982015643693572	0.0071054682003744	-0.1830412767090138	0.3994452279822500	
+5.6929999999999996	0.0352514520034233	0.0259080185086306	9.7969929894002874	-0.0836954696793373	-0.1082823381638203	0.0205994614487002	
+5.6940000000000000	0.0696385045036058	0.0197049240808052	9.8009937423028575	0.0234457585631659	0.0254591626186525	0.2544555707489363	
+5.6950000000000003	0.0711645054366529	0.0610212038262314	9.7979420212951478	0.2535560988065350	-0.0968653483541953	0.4050305631619449	
+5.6959999999999997	0.0468312864718358	0.0153852915209059	9.8002015493106853	-0.0716143975868834	0.1260716537801266	0.0530785222196551	
+5.6970000000000001	0.0675385504384717	0.0187503565979608	9.7781075173086389	0.0691737577959520	0.0532020937730987	0.0571879761114323	
+5.6979999999999995	0.0493868705823573	0.0137403927997890	9.8046787599447871	0.0264254352936503	0.0973152313879386	-0.0285329036486274	
+5.6989999999999998	0.0559988185719701	0.0113291397485536	9.7925367835801094	0.0653653184011548	0.1033529964379833	0.0003566929253019	
+5.7000000000000002	0.0884574047650966	0.0332058636775130	9.7928681382193492	-0.1863957731156317	-0.0010412506940023	0.3116850174517360	
+5.7009999999999996	0.0579415318748564	0.0305165317199031	9.7895463819978605	0.1586157315436993	-0.0699107067242747	-0.0018494903356380	
+5.7020000000000000	0.0534596370248213	0.0223510610247671	9.8088390689769351	0.2488039194531025	0.1376363523377827	0.1870319875288328	
+5.7030000000000003	0.0731847118070323	0.0207180295127604	9.7995061124345373	0.0976333719559887	0.1072561897302156	-0.1028113680385494	
+5.7039999999999997	0.0406845035824433	0.0146239023467216	9.8062997784913151	-0.0614543159032594	0.2772474045003612	0.0745891801745455	
+5.7050000000000001	0.0391602600566948	0.0094827167171169	9.8006546293128380	0.2156482637040374	0.1854510259477756	0.1891112352951152	
+5.7059999999999995	0.0556973524665517	0.0085149237103690	9.8148408939064105	-0.0548302181937190	0.1387117910187699	0.0673347875603531	
+5.7069999999999999	0.0730375522015775	0.0141456182068033	9.7965126741127158	-0.0063584631009413	-0.0211069999261838	0.2872194284255167	
+5.7080000000000002	0.0440950227945849	0.0401750638464551	9.8113252282336383	0.1359707619900108	0.0386726372473122	0.3162124933237062	
+5.7089999999999996	0.0330607676331115	0.0333172953109357	9.8012124712717892	-0.1651602519090837	-0.0044300983581964	0.0744989756575883	
+5.7100000000000000	0.0573756331593487	0.0225674817565255	9.7961919068767784	-0.0656764570700996	-0.0492316053980610	-0.0564763824862300	
+5.7110000000000003	0.0467177261690516	0.0073674969578188	9.8021818522992934	0.0407836214384520	-0.0120175761838891	0.1864272093648735	
+5.7119999999999997	0.0622584633333649	0.0173278655968953	9.7699124487141518	0.2238216061992438	-0.0067474538569178	0.0047044975883253	
+5.7130000000000001	0.0698558841346333	0.0212481680891307	9.8073484822812755	-0.0254714290667845	-0.0952384041770250	0.0126411654761911	
+5.7139999999999995	0.0608830965256937	0.0286199943111797	9.7912459379664405	0.0907844368056044	-0.0403064801821551	0.1329744157334596	
+5.7149999999999999	0.0465307898548957	0.0110257698787312	9.7939402396487303	0.1825649215432623	-0.0379427401668977	0.2294937703609828	
+5.7160000000000002	0.0595310339153380	0.0241987648932253	9.7958976547376189	-0.0034820512045513	-0.1446977816225933	0.0126747718703356	
+5.7169999999999996	0.0484901676076206	0.0240330352405813	9.8049544252916583	0.3249929803814887	-0.0630855276511464	0.1694454004404987	
+5.7180000000000000	0.0646081982025896	0.0423725918586420	9.8122564529779002	-0.0212232758840742	0.1467592941132742	0.3807723794922754	
+5.7189999999999994	0.0515477116841427	-0.0019433089635861	9.7870081026946973	-0.0550193359608330	-0.1320853002626615	0.0885683035202722	
+5.7199999999999998	0.0417480088320442	0.0247044918131413	9.7895162459521412	0.3036506270942071	0.0495835694674661	0.2021839699278460	
+5.7210000000000001	0.0482086981964982	0.0301034464384682	9.7845881087838773	-0.0990316788448138	0.0264154781126555	0.2151880002919088	
+5.7219999999999995	0.0569422263588928	0.0438381166350682	9.7910225454960642	0.2857287411134182	-0.0097286452061837	-0.1627284009407114	
+5.7229999999999999	0.0687328696545804	0.0448189672524247	9.8078410490271182	-0.0007073235859779	0.0072313153512064	0.0398165070886390	
+5.7240000000000002	0.0530559293316754	0.0294329923114954	9.7686143423525102	-0.0150393795644500	-0.0082576831045966	0.2443913097095590	
+5.7249999999999996	0.0638852881199481	0.0250553130000716	9.8062225492681847	-0.1178350340085584	-0.0719993104109550	0.0802176874843919	
+5.7260000000000000	0.0421292803680942	0.0199544854724545	9.7939303826411113	0.2427429795447317	-0.0144622953798569	0.2696982617995392	
+5.7270000000000003	0.0622468292484704	0.0166720770039046	9.7714407865828434	0.1857910149397027	-0.1087936391983814	0.0972385284800339	
+5.7279999999999998	0.0332868120797309	0.0125162210844369	9.8037563977174269	-0.0230500531377565	-0.0809810136612202	0.0928721200615132	
+5.7290000000000001	0.0489471281806679	0.0345894738030141	9.7918988664279727	0.2160136313951548	-0.1626498408736984	0.2907619991405732	
+5.7299999999999995	0.0619829202668053	0.0229981892422035	9.8056535894328061	0.1365336015744502	0.1742696891672443	0.0566443696089285	
+5.7309999999999999	0.0492634786447870	0.0423903283481728	9.8077878664021014	-0.1235832379836838	0.0492681550126374	0.1869868110546579	
+5.7320000000000002	0.0582006359014470	0.0191229732911762	9.8006447852819711	0.2002712257511937	0.0178304351819423	0.0733331344751021	
+5.7329999999999997	0.0836100810370684	0.0307647596132702	9.8109703076256842	0.1769443550546433	-0.0012301899286618	0.2363732644057516	
+5.7340000000000000	0.0479891832033194	0.0323316078086408	9.8065310630667408	-0.1491971399258211	-0.1486552207941979	-0.2293182812421964	
+5.7349999999999994	0.0461122670686151	0.0228608442783970	9.7999839435590150	-0.0316329182576284	0.2835075387381630	0.2437412088037701	
+5.7359999999999998	0.0668601859854685	0.0238117393394292	9.8020927339430948	-0.0219746308980228	-0.4320200531353536	-0.0010721952242946	
+5.7370000000000001	0.0680096495000762	0.0222065531954239	9.7976486710587416	0.0174854466980228	-0.0170310654422025	0.1859214344702491	
+5.7379999999999995	0.0425455315484670	0.0296526557378588	9.8099044518095493	-0.0687280192039514	0.0747564693854134	0.1408973344833575	
+5.7389999999999999	0.0562268028776308	0.0210298450183440	9.7956882707832094	-0.3654434937737042	-0.0058796898147900	0.2237956531825653	
+5.7400000000000002	0.0562671351181043	0.0222431862076385	9.7750829299950777	-0.0866536664059103	0.1118798544871235	-0.1540161060104596	
+5.7409999999999997	0.0560892842648695	0.0221711548246649	9.7954576464254259	0.0100905323387129	-0.1366628587338704	0.1752691670725797	
+5.7420000000000000	0.0785853088193345	0.0347135398003489	9.7995103633613692	-0.0113038259729247	-0.1121645695216591	0.2625567858445285	
+5.7430000000000003	0.0580799197585625	0.0292779997176833	9.7703339606852904	0.0885941256581219	-0.0139455993518407	0.0208601086251954	
+5.7439999999999998	0.0733292373941175	0.0320630868302231	9.7777516637487079	-0.0180218401355958	-0.2134881407985578	0.0566454570489801	
+5.7450000000000001	0.0702148428677192	0.0254174544436255	9.8069353695826784	0.0571327578738989	-0.1245476911995778	0.4179447805113775	
+5.7459999999999996	0.0855322907760088	0.0064101256953538	9.8069102824891825	0.0648453124736785	-0.0855590210673460	0.0532587352467777	
+5.7469999999999999	0.0584755490148839	0.0314631949938522	9.8030104239929923	0.1010333705467074	0.1981423896679289	0.3461924758778769	
+5.7480000000000002	0.0595901743767629	0.0374699014416797	9.8120530296064725	0.0104571720259025	0.2034164987897507	0.2334085783126932	
+5.7489999999999997	0.0560604424477330	0.0247377157159218	9.7988007920158413	0.0615992581394347	-0.0254912957584136	-0.0143354402082274	
+5.7500000000000000	0.0631434255280168	0.0184345633650320	9.8063096531727822	0.0104698110998469	-0.1587727797599240	0.1909133083925278	
+5.7509999999999994	0.0636055200691846	0.0244750559707455	9.7866050931747850	-0.0917730839986095	-0.0338681120018390	0.0169366171821319	
+5.7519999999999998	0.0698753083457849	0.0103508343555223	9.7983620876128903	-0.0039905094707134	0.0495339466274123	-0.0471703167461943	
+5.7530000000000001	0.0691447851732939	0.0175031310034993	9.8056298125535477	0.1181827125211151	0.0198420396663771	0.1919091200461754	
+5.7539999999999996	0.0790508565345953	0.0031787962329444	9.7888725462429917	-0.1367628789341384	0.0844371703451545	-0.0599883451775800	
+5.7549999999999999	0.0803551585441181	0.0151400025892994	9.7878962149087378	-0.0583985963814674	-0.3998226946377811	0.4048503988772357	
+5.7560000000000002	0.0692707163166180	0.0168389793622614	9.7649111210613828	-0.1678497833645883	-0.1156672373457247	0.1393752620110319	
+5.7569999999999997	0.0622246592391902	0.0257891769609463	9.7757124172935903	0.3591982466212466	0.1068213915884733	0.1322247023766301	
+5.7580000000000000	0.0676856564764202	0.0191911426717416	9.8139080238963778	-0.1445388848319129	0.1879364170476334	0.1782699386995688	
+5.7590000000000003	0.0535129419797354	0.0428992963390669	9.8055317387763914	0.1406188169755371	0.0051493274155094	-0.1431623967373289	
+5.7599999999999998	0.0594347985294651	0.0227086280831173	9.7935188109248585	0.2113214096773230	-0.0334566494780411	-0.1703686167928342	
+5.7610000000000001	0.0592558743870538	0.0377796862667658	9.7817828990950701	-0.0334264938110608	-0.0171904324693345	0.0221885552275285	
+5.7619999999999996	0.0620697655570163	0.0249300286807022	9.7950856515486553	0.2113381699481768	-0.0882873095526917	0.0180662319108659	
+5.7629999999999999	0.0561381651598171	0.0315867757102229	9.7833173703533021	0.0752905706622465	-0.2937753912005595	0.0164412995030128	
+5.7640000000000002	0.0612208150195843	0.0409787382965871	9.8046778710551159	-0.1977533392064523	-0.0112242178884344	0.2655661987375671	
+5.7649999999999997	0.0691192348585711	0.0154635961804887	9.8139155357078298	0.2490663367861569	0.0318536059522679	0.0505392993349017	
+5.7660000000000000	0.0219821591245781	0.0296671614749211	9.8083444168277083	0.1634350778595871	-0.0104263123182038	0.2027519188760711	
+5.7669999999999995	0.0706782532353515	0.0276503268711243	9.7974569076898703	0.1485806014892411	-0.2733577231310780	0.3410598732077118	
+5.7679999999999998	0.0396543193529347	0.0186254962102827	9.7766699029453754	0.2816063933776642	-0.1324384143143894	0.0975811734067613	
+5.7690000000000001	0.0679151194098559	0.0222179518734443	9.8027115084941556	0.0937931637644979	-0.0841014832590616	0.0569075167769419	
+5.7699999999999996	0.0636557122683140	0.0431705211942415	9.7916112306136895	-0.0270103089926668	0.1731138752330192	0.0620219365369781	
+5.7709999999999999	0.0541195147090734	0.0266661217252444	9.8299384852351253	-0.2512106205072522	-0.0251071694825059	0.2795073257093562	
+5.7720000000000002	0.0438914028376006	0.0401772130874722	9.8183490193651544	0.2159329020112285	-0.0644833098022783	0.1487328469847740	
+5.7729999999999997	0.0497392759989094	0.0362492666371483	9.7834756316958078	0.0162970745793224	0.2169949583843805	0.2590164847644394	
+5.7740000000000000	0.0715218038673874	0.0208613008247665	9.8009913126087316	0.0976195910445234	-0.0441059097820903	-0.0759425146786672	
+5.7749999999999995	0.0737532411142740	0.0192894465881701	9.7817278461515951	0.0793220590963960	0.0759769493788989	0.2797041103176681	
+5.7759999999999998	0.0767016705619700	0.0439399956627794	9.8150375210863725	0.1042264815643439	0.0492860019209253	0.0115958843089031	
+5.7770000000000001	0.0525660207286524	0.0219759715276610	9.8109157651381285	-0.1956896884555464	0.0866423897316344	0.1481969336366583	
+5.7779999999999996	0.0862588282024514	0.0215088758329098	9.7767922208280336	-0.0091997140068886	0.1161361657872139	0.1261159434040349	
+5.7789999999999999	0.0562801113294552	0.0257332667725892	9.8025823391771834	-0.0607723859003024	-0.0652503154640991	0.1453920515509080	
+5.7800000000000002	0.0747581185378337	0.0423520313988619	9.7892369173779290	-0.0048337609470095	0.1325674392451221	0.2744577032204676	
+5.7809999999999997	0.0800307859209013	0.0328343331436532	9.8012945206716715	-0.1759628012659963	0.1474859875903101	-0.0836131663269705	
+5.7820000000000000	0.0702997207080644	0.0080444846053795	9.7873937637336983	-0.0293059874920635	-0.0102819239705084	0.1718757739599262	
+5.7829999999999995	0.0849304776175165	0.0230640011557879	9.8013905654726958	-0.0015509426309809	0.0803757392114744	0.0442342350346428	
+5.7839999999999998	0.0575628830627233	0.0078294683621307	9.8003354922413894	0.0765825930878420	0.1025623849637897	0.1215950775586287	
+5.7850000000000001	0.0453165950426475	0.0270072098071539	9.8031903029549756	-0.1561505473076703	0.1721585187774883	0.0873128773859237	
+5.7859999999999996	0.0458082606695271	0.0335077504751014	9.7950629974910939	0.1918646611653297	-0.1962902980750645	0.2323532147147648	
+5.7869999999999999	0.0621860967937974	0.0293480406544125	9.7872062175613852	0.0364479320201675	-0.1545768156110669	0.1364217865866114	
+5.7880000000000003	0.0439518356881239	0.0306408008439543	9.8013208722197440	0.1857141511305526	-0.0218736945268308	0.0653662151854223	
+5.7889999999999997	0.0524546325605848	0.0301883712135815	9.7998700344671263	0.1435449067698346	-0.3536534144895788	0.2150905737314428	
+5.7900000000000000	0.0569640098616610	0.0192335170790703	9.8002331472176429	-0.0680491713919843	0.1344982910927730	0.0880147058799198	
+5.7909999999999995	0.0657497194143016	0.0356754668206186	9.8073580984038902	0.2007728024455319	-0.3094358161509986	0.0637492066862053	
+5.7919999999999998	0.0355876874498009	0.0199288226501888	9.7873167923912181	0.0687028849453369	0.2883190412410905	-0.0083021477540959	
+5.7930000000000001	0.0562735825327241	0.0131377253806700	9.7794496177816903	0.0379866870860408	-0.0012650703686847	-0.0528309204689364	
+5.7939999999999996	0.0574990707875134	0.0436838639582080	9.8034982388239182	-0.2379875289312359	-0.1538203100176765	-0.1947933013156242	
+5.7949999999999999	0.0541763123135334	0.0163780481729922	9.8052167873680567	-0.0140361837747981	0.0157263108908838	0.1113174541204478	
+5.7960000000000003	0.0626632679948665	0.0148277407424655	9.8044491902536599	-0.1718244721451619	0.1258750876145691	0.0492990668160367	
+5.7969999999999997	0.0533451145955022	0.0357394707396438	9.7995382623840221	0.0994292043948997	-0.0639708515192660	0.2857074040654417	
+5.7980000000000000	0.0533919217552336	0.0402968612685146	9.8092061265675348	0.1126052847948676	-0.1509068629801215	-0.0234889723815202	
+5.7989999999999995	0.0394799290105961	0.0291225980362595	9.8101966894925816	-0.0184823576249706	-0.0537658702696997	0.0787786858904692	
+5.7999999999999998	0.0692871137206526	0.0165888399573870	9.8075111861052076	-0.0339064238538809	-0.1713895490614261	0.2029935485288075	
+5.8010000000000002	0.0655577951623376	0.0204558567130974	9.7814635362411355	-0.0930426970762888	-0.1433528433686324	0.0855578937498194	
+5.8019999999999996	0.0681052567226636	0.0400679443806998	9.8047376206430545	-0.2556465931501480	-0.1538881918042740	0.2233912886230748	
+5.8029999999999999	0.0778728483838972	0.0213690466769001	9.8035605975972739	0.1566309618344456	-0.1500807342356673	-0.0048565602107137	
+5.8040000000000003	0.0652333185237174	0.0308912516344290	9.7978885295684215	-0.0212714204931050	-0.0565441071557793	-0.0607288546647348	
+5.8049999999999997	0.0512018659466825	0.0462800360392668	9.7912551125235847	0.1759898435020596	-0.0243422309536130	0.0727987185261803	
+5.8060000000000000	0.0539122305713449	0.0404772244930014	9.8089909824203048	-0.2176977672514719	0.1208955970295736	0.1625034520819736	
+5.8069999999999995	0.0507980643145498	0.0211448943946506	9.8062182745065289	0.0883595710781634	-0.1265064689413487	-0.1236234106508849	
+5.8079999999999998	0.0630087565888524	0.0499289767154866	9.7979678467389881	-0.0709014874098821	0.0377811593096487	0.1281876987242997	
+5.8090000000000002	0.0647991223883534	0.0372553576354126	9.7959288836432723	0.3837930636213202	0.1886891330596993	-0.0435178561693182	
+5.8099999999999996	0.0622393712742326	0.0288241110602630	9.8033721018805569	0.0243329919160923	-0.2877906687653812	-0.0110794146696862	
+5.8109999999999999	0.0477042845402814	0.0313050126923938	9.7955412007563538	0.1940434681537541	0.1104574397839518	-0.1309651508963758	
+5.8120000000000003	0.0547759266184789	0.0332096925494524	9.7952058394135335	0.1947116501986390	-0.0362152205477337	0.2445195714297181	
+5.8129999999999997	0.0505292444404340	0.0173425175779092	9.8038916895045620	0.2658455645596720	-0.0897089898414428	0.0793668875424765	
+5.8140000000000001	0.0372893879609322	0.0477029136983837	9.8191279417040391	-0.0790749885009715	0.0195747878508508	0.2410405382957190	
+5.8149999999999995	0.0372862255461804	0.0154603308809029	9.8012731908132515	0.2340390027937924	0.1532351272685701	0.1500296229202147	
+5.8159999999999998	0.0557488523077268	0.0182625392638364	9.7908536076844204	0.1599742846962318	-0.2314449477572603	-0.0799253146142713	
+5.8170000000000002	0.0590829209755064	0.0429061055193509	9.7908888082040182	-0.3215189562771621	0.1519613558524634	0.2319107658089634	
+5.8179999999999996	0.0480833194413034	0.0129900918740973	9.7917889365919173	-0.0500304775628775	-0.1201309424878506	0.0626781400516621	
+5.8190000000000000	0.0617434812120061	0.0391805609486053	9.7873298425935573	0.1137008162284349	-0.0652741390820864	-0.1838754355407171	
+5.8200000000000003	0.0629460984566663	0.0151222457417508	9.8187759089469910	0.1983366029970768	0.0126636653956903	0.1446451112520098	
+5.8209999999999997	0.0569443679049479	0.0279208359325564	9.7974333925245833	0.2333179840431208	-0.2901088898567598	0.1813130168734531	
+5.8220000000000001	0.0481099936979510	0.0249835870761857	9.7778502951729198	0.0674636425198678	0.2607305002735738	0.1195378456721821	
+5.8229999999999995	0.0671883046116775	0.0332266113858897	9.7910763973679114	0.0496482285191458	-0.1909117911721734	0.1911536742778246	
+5.8239999999999998	0.0838838921005494	0.0165276709561019	9.8005626094745590	-0.1979212463581392	-0.0113622034901386	-0.2265882279763750	
+5.8250000000000002	0.0507342550804849	0.0501260783342001	9.8045476993627840	-0.0191952123312790	0.0591753543131628	0.2938797478742448	
+5.8259999999999996	0.0580281707928938	0.0014677587131623	9.8007225689232591	0.2187567423959298	-0.0353686424746321	-0.0239367958914857	
+5.8270000000000000	0.0596381458210147	0.0519895905796279	9.7720450807695354	0.1964173095503507	-0.1141943470352903	0.1245876582737406	
+5.8280000000000003	0.0638050819710404	0.0278134254828645	9.8072677810819080	-0.1135968880648290	-0.2494624218954170	0.0723209486659785	
+5.8289999999999997	0.0618706292326726	0.0264414299876405	9.8062153563565992	-0.1478591570523736	0.2691059053980372	0.0429326292252471	
+5.8300000000000001	0.0405120889429166	0.0191897081400924	9.8128844485778259	0.0275032252708405	0.0892843801652435	-0.0423668531302272	
+5.8309999999999995	0.0646245966684850	0.0330385896936885	9.8001086166468276	-0.2843986466262650	-0.0066148855489334	-0.0038481870321025	
+5.8319999999999999	0.0444926791269191	0.0349283817487873	9.7889920435180322	0.0468268726126586	0.1902659831280198	0.1319282559434892	
+5.8330000000000002	0.0458857026050125	0.0117607069939690	9.8054425783505437	0.1642120008083764	-0.0157198991868671	-0.0446409277123939	
+5.8339999999999996	0.0584905409262220	0.0211631338714550	9.8062233914531021	-0.0145766857216027	-0.0359981484991476	0.0273050609174399	
+5.8350000000000000	0.0554036170995927	0.0401312737573146	9.7837037549375481	-0.1785712991553607	-0.2895108303008301	-0.2238168896160534	
+5.8360000000000003	0.0661719805552599	0.0006028041404239	9.8084105267327502	0.2982326689504937	-0.0079680733584749	0.2107595187733543	
+5.8369999999999997	0.0731772016033945	0.0239100647753199	9.7782346988856972	0.0805337796657392	-0.1195717907494854	0.0961878055672201	
+5.8380000000000001	0.0625965663600274	0.0345835009699327	9.7997867696572847	-0.0802003470572487	0.0238205695175650	0.0481706687212632	
+5.8389999999999995	0.0567155746352004	0.0349945060730484	9.7902144619875227	0.0708847340825379	0.0513318098521904	-0.0543775810179412	
+5.8399999999999999	0.0542134447179829	0.0152503490881816	9.7938255884561407	0.0022248946268559	-0.1973265377467295	0.0357625073280330	
+5.8410000000000002	0.0587922204007508	0.0392149078331397	9.7875626423728299	-0.0114716571028845	-0.0903022463555339	0.2748469606601094	
+5.8419999999999996	0.0796316220067973	0.0100481481431763	9.7872525798764052	0.1475474764072044	-0.0302407736368216	-0.0872443734928841	
+5.8430000000000000	0.0539207523733276	0.0342664254661670	9.8093896733520722	0.1893055584281684	-0.2623513322461057	-0.0349298281751917	
+5.8440000000000003	0.0359651275536902	0.0076969939222868	9.7983596891679579	-0.0301514495656429	0.0486472065102458	0.1137290168201114	
+5.8449999999999998	0.0520312266716798	0.0395873086250882	9.7777785498293106	-0.0269311909512768	0.2482308747018457	0.1078091131430294	
+5.8460000000000001	0.0514534188896997	0.0175088268896183	9.8034650300993853	-0.0077067022417395	-0.0228031412177423	0.2641706277497254	
+5.8469999999999995	0.0500078636335299	0.0289178226606566	9.8155410383647368	-0.2461285569100801	0.1014345209544473	-0.0275452699740935	
+5.8479999999999999	0.0548631396215171	0.0384174166952294	9.7650179489800308	-0.4725488937585338	0.0532829150369486	0.0083212775032334	
+5.8490000000000002	0.0576662314697695	0.0295547519158556	9.8094640516488667	-0.0995573631503377	-0.0879190408342288	0.1070156460036348	
+5.8499999999999996	0.0215051669866287	0.0432212111070117	9.8041849636959686	0.0975768508161502	-0.3006689023240370	0.4051003762485602	
+5.8510000000000000	0.0616844972733632	0.0324562199679075	9.7806235444254259	0.1811452750102550	-0.1711820445701495	0.1028583262398528	
+5.8520000000000003	0.0489130243469147	0.0115124397798129	9.7739212029803451	-0.0373397486423142	0.2447194110375900	0.2151686227104074	
+5.8529999999999998	0.0722588492910631	0.0361790121617343	9.7960423976568070	0.0522450912034396	0.0860076249248550	0.3321548446633522	
+5.8540000000000001	0.0488100845568724	0.0281601763039547	9.8076174919642298	-0.0236505918786966	0.1493906316609281	0.2136390162428070	
+5.8549999999999995	0.0647683868345705	0.0301632661223449	9.8039686448903858	0.1275129147869517	0.0190499406313434	0.3195943173210640	
+5.8559999999999999	0.0693582789535335	0.0114886091630409	9.7984761661793858	-0.1198920110599917	-0.0299614755932822	0.0792410788038146	
+5.8570000000000002	0.0624053373347027	0.0335542025517362	9.8076744775605018	-0.0549650741340097	-0.0511813909161800	0.1067559278975495	
+5.8579999999999997	0.0396576907332954	0.0310396824386543	9.8163982016095837	0.2492530466474227	0.0052058772604574	0.1093752197424442	
+5.8590000000000000	0.0537859825278364	0.0213097205549774	9.8113857483501619	0.2064661947913556	0.0124675693751956	0.3031567513110945	
+5.8600000000000003	0.0599422416664696	-0.0062769123197368	9.8157029085409828	-0.1303822031146363	-0.0557512881479260	-0.0317275491773080	
+5.8609999999999998	0.0752131476013273	0.0100438972700621	9.8070232879936423	0.2380239870457073	-0.2835632694228174	0.2630015386360097	
+5.8620000000000001	0.0696125652115858	0.0237133147762506	9.7844839268798172	0.0873917605014757	-0.2091670238536307	-0.0232074490161597	
+5.8629999999999995	0.0463056207810281	0.0227586255314024	9.8001027115734765	0.0323174945988964	0.2829409841143430	0.1089037201308836	
+5.8639999999999999	0.0593427646259045	0.0409560828670600	9.8092747733125520	0.0142520203156522	0.0003023039337230	0.2217086624342252	
+5.8650000000000002	0.0403645556842458	0.0226891627836588	9.7906984523319718	-0.1114731063874176	-0.0897917919168077	-0.0519221880375411	
+5.8659999999999997	0.0676014251997514	0.0200554722255138	9.7893189444018294	-0.0356707845588475	-0.1265106714465107	0.3499602930664923	
+5.8670000000000000	0.0595621057929769	0.0328693522910750	9.8175155931682845	0.1933704398357989	-0.2603093667975904	-0.1904220389588681	
+5.8680000000000003	0.0701496576661000	0.0039108199576851	9.7958638860467726	0.1020600659370912	-0.2145254578154740	0.1283241134306807	
+5.8689999999999998	0.0828295114804074	0.0188369285553554	9.7901037931441302	0.2149785324408282	-0.0131582201355038	0.0947196440722514	
+5.8700000000000001	0.0465363771295605	0.0101824081349333	9.7965986679696897	0.0501124701242182	0.1932180401863952	0.0394997985065775	
+5.8709999999999996	0.0600027847259332	0.0369871666275540	9.7979321128131343	0.0516112737287583	-0.0793348628318770	0.0120641819399449	
+5.8719999999999999	0.0631107289168105	0.0158612972760200	9.8210116962290908	-0.0250006235797303	-0.0786874893983651	0.2966028205991169	
+5.8730000000000002	0.0753418234165261	0.0085432584264253	9.8051163105043475	0.1482597417169780	-0.1018821270768108	0.2266232129592783	
+5.8739999999999997	0.0704323642837159	0.0116585016792167	9.7854179472989031	0.0033301405201681	-0.2382958213599940	0.2193253468001287	
+5.8750000000000000	0.0761934854446441	0.0125138489424526	9.7933730671681207	0.0763912614790992	-0.1287056435842810	0.2877814864319675	
+5.8759999999999994	0.0642510066952572	0.0357343622206005	9.8051616876247092	-0.0300662075804584	0.0035176368220774	0.0237394727714461	
+5.8769999999999998	0.0759918307786051	0.0283029518019622	9.7776262510984040	0.3499684855830832	0.1019723591819373	-0.0107668690998034	
+5.8780000000000001	0.0362343632284039	0.0363629394375833	9.7983576267440533	0.0719187255757385	-0.0539457157701615	0.0822045005665487	
+5.8789999999999996	0.0458710298121037	0.0554872135868738	9.7944866848574073	0.0351058180308837	0.0368798233335360	0.2632823087899398	
+5.8799999999999999	0.0709712292672012	0.0508417718667569	9.8037248241261707	0.0825840008827882	0.1495810020594151	0.2589425019010501	
+5.8810000000000002	0.0507456099242859	0.0343295524162594	9.7922165788343474	-0.1338883659578294	-0.0920055680279919	0.1058915095444865	
+5.8819999999999997	0.0582885081781281	0.0163131506577149	9.8037695455096472	0.2121180650813638	-0.1514384447839686	0.1129215398181787	
+5.8830000000000000	0.0623094029424938	0.0385726748008078	9.7995870056402357	0.1883148536450715	0.0359295715568255	0.0119263049393042	
+5.8840000000000003	0.0577493175321888	0.0541500531121888	9.7928091085458728	0.3003341915125295	0.0002292699745982	-0.1630482341444995	
+5.8849999999999998	0.0565391922590343	0.0258900227888976	9.7791732055373455	0.2167760452450113	0.0721783022459262	-0.1013881857620118	
+5.8860000000000001	0.0620348825922535	0.0169398550239883	9.7874032629462917	-0.0759346117150681	-0.0953296753965346	0.0845295040873565	
+5.8869999999999996	0.0574598056543648	0.0401733926693476	9.8260024681792562	0.1666332180710052	-0.2729409783064285	0.2886843759563203	
+5.8879999999999999	0.0708657237490383	0.0243684009978601	9.7877551117329880	0.0045519020648533	0.0071048336052077	-0.0919585911925731	
+5.8890000000000002	0.0695415615508734	0.0406317825826987	9.8133432505629035	0.1825649048885808	-0.2063773172913990	0.1116948348797529	
+5.8899999999999997	0.0561586361413242	0.0268530350256248	9.8055221398049834	-0.0090927415336798	0.1429017923623161	-0.2294668553227036	
+5.8910000000000000	0.0557130697492966	0.0327314189080422	9.7757390775647224	-0.0114528975666793	0.0420058719941543	0.2689996578111866	
+5.8919999999999995	0.0803713587400277	0.0264378589090699	9.7915603402510225	0.2415611369039815	-0.2330116783997919	0.0219527251306398	
+5.8929999999999998	0.0479637967476325	0.0175891254596417	9.7950870608671057	0.1303943487095833	-0.0589533009329712	0.0165128862876165	
+5.8940000000000001	0.0844037685108019	0.0494286974318665	9.7967255363423504	0.0036625637307920	-0.1060180248330465	0.0778719062415682	
+5.8949999999999996	0.0587638041776279	0.0197978371653337	9.8102175206526372	-0.0191159946452021	0.2121399023192541	0.0809558738298041	
+5.8959999999999999	0.0490015359078207	0.0043117355133959	9.7867514381436003	0.3791528521926072	-0.0001962849066347	0.0208062987547782	
+5.8970000000000002	0.0802985129132560	-0.0006401139704620	9.8088880611254652	0.2667700105155546	0.0297083863178015	0.1674408602665392	
+5.8979999999999997	0.0668380027301580	0.0456170719040917	9.8047766315817828	-0.0308903291862370	-0.1987582993065646	0.0636423974556449	
+5.8990000000000000	0.0535958434141667	0.0545871062921048	9.8157104558062453	0.1114806783070110	0.0933576866933030	0.2578600734580959	
+5.8999999999999995	0.0315483122112259	0.0244301983273996	9.7851199878240909	0.0420595977023872	0.0800297627608467	0.0958152788294253	
+5.9009999999999998	0.0574077850581486	0.0274677591947958	9.7848176600328447	0.1737414461947464	-0.1590793033926972	-0.3873935663846054	
+5.9020000000000001	0.0564327875006519	0.0291003331390436	9.8027509984227290	-0.0121975667106203	-0.2154727552479057	0.3487138039555431	
+5.9029999999999996	0.0506602295819602	0.0083678662660852	9.8097543606919189	-0.0690359469277748	-0.1573416614292494	0.2489014676962520	
+5.9039999999999999	0.0656557919011411	0.0253544426789951	9.7931463049011729	-0.0588023572290036	-0.2558888849926159	0.0900651085716630	
+5.9050000000000002	0.0429788015716993	0.0161867746839357	9.7760810741225246	-0.1017135601728256	-0.1459678134835508	0.0460359500437742	
+5.9059999999999997	0.0621956300114897	-0.0035778282230951	9.8043663740938936	-0.0504267129070581	0.1437765099607249	0.1365821431379346	
+5.9070000000000000	0.0508284012110649	0.0140958024581585	9.8091856040655152	0.1714945066414505	-0.0455840189960393	0.2618298034180070	
+5.9079999999999995	0.0597846022203234	0.0118188872304177	9.7815358069510339	0.0885597289864972	0.1243025804000119	0.2876697139651890	
+5.9089999999999998	0.0659907623832518	0.0411024034974026	9.7989752163933765	-0.1978559140517360	-0.0174696652555225	-0.0196459248183069	
+5.9100000000000001	0.0531239650497316	0.0162196616741775	9.8105740765204263	0.2241282417400295	-0.3516713778658641	0.0531768838242561	
+5.9109999999999996	0.0752390849543279	0.0413981335087091	9.8027676120893155	0.1954914920098026	-0.1152127094215565	-0.0294568663255268	
+5.9119999999999999	0.0630061476430656	0.0153831148608741	9.7854559808147918	0.1478452197612828	0.1396768921490594	0.0714956504146213	
+5.9130000000000003	0.0705989963026852	0.0254754789508023	9.8327187763899193	-0.0121541471194902	0.0169396087162772	0.1045179527360179	
+5.9139999999999997	0.0734669406480552	0.0356198388557786	9.7955690402203537	-0.0601215876378355	-0.1354407363268336	0.1595975102743869	
+5.9150000000000000	0.0534376538686116	0.0522160378649703	9.7982597990500420	0.2112437874049550	-0.0152804198399813	0.0528076999004324	
+5.9159999999999995	0.0772965284489337	0.0225336276534204	9.8055430169309599	0.1190031475899951	0.0885391495789818	0.0232833263235509	
+5.9169999999999998	0.0597577192324224	0.0197886959586244	9.7868460439976275	0.2744740776526775	-0.1958337543590049	0.0386622726157455	
+5.9180000000000001	0.0903213210272459	0.0198329465183634	9.7954986944766542	0.1775793315639004	-0.1816476459880285	-0.0201144737771277	
+5.9189999999999996	0.0637826080991346	0.0229261962166802	9.7836200976431549	-0.1561490863707982	0.0527998586621557	0.0240277394714470	
+5.9199999999999999	0.0619381199211137	0.0126677377927954	9.7978219440959116	-0.0277894774610247	-0.0996078978844631	0.1026937173016996	
+5.9210000000000003	0.0394772583588346	0.0252294450786641	9.7988827253963358	0.2713407739759408	0.2185505344802917	-0.0904542102035470	
+5.9219999999999997	0.0644750836423210	0.0265393340178317	9.8099372676328329	-0.0702991868479164	0.1147990355659985	0.1138554002806607	
+5.9230000000000000	0.0498900014304025	0.0141688200100113	9.7955136124129822	0.1201840081804991	0.1149231546899353	-0.1646365308225113	
+5.9239999999999995	0.0463267357757722	0.0201039000355464	9.7934884516574705	0.2352561630745636	0.0513255067498335	0.0410286008512021	
+5.9249999999999998	0.0561471779609172	0.0269663243489607	9.7969537719271358	0.0813748887603072	0.2765719104603132	-0.1038675472943552	
+5.9260000000000002	0.0748783832061419	0.0380230700499642	9.7855100629211762	-0.2383581918088749	0.1187512520185899	0.2752333588671075	
+5.9269999999999996	0.0574820940963691	-0.0026997235047858	9.8110654547350329	0.1440895513057009	0.0240449714771286	-0.0685857521449671	
+5.9279999999999999	0.0417232182840680	0.0149573488610517	9.8112894058984530	-0.0061493169350220	0.2267438195758842	0.0627920294065490	
+5.9290000000000003	0.0664168768192656	0.0067148422242416	9.8015537079231674	0.2674357560486711	-0.0101192055203289	-0.0349870071205248	
+5.9299999999999997	0.0429993831007830	0.0389457623943108	9.8017386154338961	-0.1453670854788421	0.3604999921306527	0.0343610872347470	
+5.9310000000000000	0.0457285420806642	0.0141135463557004	9.8194111917783911	0.1444265369119349	0.1652104031291780	0.1528128877243678	
+5.9319999999999995	0.0587545615678373	0.0172893806970186	9.7952939712412945	0.0376603958015560	0.3436127101466154	-0.0409314336690621	
+5.9329999999999998	0.0587820985493365	0.0088172136510449	9.7983242065081626	-0.0029382900761484	0.1559998931156894	-0.0097266886029966	
+5.9340000000000002	0.0612841684355543	0.0444459521289979	9.7917568457308963	-0.1761491523186637	0.0075813506390029	-0.0606175334649354	
+5.9349999999999996	0.0617142823152402	0.0538836710764782	9.7871441628000575	-0.0275815371238196	-0.0606888189772614	-0.1523055560700984	
+5.9359999999999999	0.0550774612718182	0.0337942366179360	9.7840711804780174	0.3616695762852500	0.0903630300064640	-0.0647191771673402	
+5.9370000000000003	0.0778393565626528	0.0248548036165171	9.8114607513938417	0.2702327355092894	-0.2647360357770618	0.0544998335829979	
+5.9379999999999997	0.0673890296693326	0.0092013824918735	9.8185917166195971	0.1983216851373860	-0.0130663878012563	-0.0380647394747438	
+5.9390000000000001	0.0521140415041999	0.0295956529839307	9.7887660583503617	-0.0490160593521131	0.2217490260446553	0.0950096388970787	
+5.9399999999999995	0.0429810542790608	0.0112579954656114	9.7740935355116463	0.0727554682202037	0.0961414319456994	0.3406327113171434	
+5.9409999999999998	0.0691499357410683	0.0244301293173944	9.7987658806814064	0.1780519841423652	-0.1379510833023778	0.0652773613247290	
+5.9420000000000002	0.0608129584490332	0.0359436036495099	9.7977680288079085	0.0774367615575799	-0.0308194841177663	0.0531082380419091	
+5.9429999999999996	0.0703444404932747	0.0271240418193507	9.7985400702944645	-0.1884494171860337	-0.1325625731748810	0.0610988113699947	
+5.9440000000000000	0.0614471264790303	-0.0024637846644188	9.7686547260793191	0.1811946176600622	-0.0533124185946044	0.0834100320936911	
+5.9450000000000003	0.0754083089381713	0.0033600212924782	9.7943376084845113	0.0987530598139526	0.0406136550695756	0.1699833641751593	
+5.9459999999999997	0.0487652834394675	0.0308096387483888	9.8065293626605374	-0.0177350774273013	-0.1226438476178097	-0.0200026647749460	
+5.9470000000000001	0.0501650777721740	0.0238478359134951	9.7907372782099014	-0.1328831449700393	-0.2769704547542176	0.2072113774415437	
+5.9479999999999995	0.0695637828144084	0.0207265488694780	9.7817544480211449	-0.0223501776869922	0.0439633039764538	-0.2253993233163910	
+5.9489999999999998	0.0627146195220870	0.0244981762672433	9.7790350623349678	0.0397314268072536	-0.2472785535500707	0.0581158773617219	
+5.9500000000000002	0.0632026674965293	0.0304706808310139	9.7863993470542852	0.1271242998389206	-0.0477170486723849	0.2755204066610676	
+5.9509999999999996	0.0547970715357510	0.0211501111618136	9.7904935837619362	0.1865263179477928	-0.1337104237785670	0.1907667062673135	
+5.9520000000000000	0.0766783425529568	0.0182058938208747	9.7943712410404551	-0.2906875829818236	-0.1653171600297203	0.0335530762493614	
+5.9530000000000003	0.0629960835159747	0.0209478053135581	9.8066093544147162	0.0847063709581077	0.1769299158529857	0.0158082273076602	
+5.9539999999999997	0.0806106712587258	0.0302795807812478	9.7920416946105515	-0.1317751822997283	0.0780189241836462	0.0268155569095665	
+5.9550000000000001	0.0666385557781291	0.0316277228140855	9.7740872672560322	0.0164002000155441	-0.1438140121728527	0.0763662880197944	
+5.9559999999999995	0.0398409330503328	0.0225211149777741	9.8163183588473100	-0.1893068455805134	0.0239882682449355	0.2451778811216405	
+5.9569999999999999	0.0468170530536598	0.0222274704700867	9.7878210714092759	-0.0374446993819529	0.0020972570759322	-0.0721598335207166	
+5.9580000000000002	0.0757956493829110	0.0170712388838177	9.7912909888933140	-0.0729641268283141	0.0001134909018236	-0.0150250427930970	
+5.9589999999999996	0.0524331747473210	0.0215840515216872	9.7993474785514501	-0.0206018794279958	0.1077722255095087	0.0657550274151143	
+5.9600000000000000	0.0583604590039741	0.0287392462092583	9.8047408869586761	0.1625006689103487	-0.2726223141608292	0.1237398011664062	
+5.9610000000000003	0.0592586162118441	0.0226030316907649	9.7891637057481500	0.2084447488731484	0.1054506838676653	-0.0159474621939228	
+5.9619999999999997	0.0602258345343788	0.0375789843702189	9.7836579848581131	0.0562183351265597	-0.0694082427001005	0.0573317178148178	
+5.9630000000000001	0.0613557558144737	0.0179083918488613	9.7912783404832773	-0.2217556870410101	-0.1998166060502995	0.2835411666019116	
+5.9639999999999995	0.0655422614302363	0.0238595811038942	9.7833417169178301	-0.1365158655803712	0.1734428221328007	0.0991391064386663	
+5.9649999999999999	0.0579534635732304	0.0065229329049167	9.8218360755891290	0.1267875101971677	-0.0865199128434874	-0.0837228816197406	
+5.9660000000000002	0.0746563442469381	0.0045871323601487	9.7940339706690942	-0.0629070576946027	0.1228637391374720	0.1598612780298205	
+5.9669999999999996	0.0570411183377884	0.0055138542458079	9.7644493204655500	-0.0113983340483119	-0.0174679487889199	0.2222241145733891	
+5.9680000000000000	0.0639638727496365	0.0378337556872136	9.7968721998312382	0.0215892466561044	-0.3713164538201069	0.2325906721917568	
+5.9690000000000003	0.0651608235212302	0.0316373933425743	9.8077378077519501	-0.0089919456679191	-0.0448444250892273	0.2174802479094337	
+5.9699999999999998	0.0669241096464526	0.0213301406955477	9.8059820883367497	0.1551526442334395	-0.0875629156185703	0.0034972884830312	
+5.9710000000000001	0.0470440648947600	0.0064418576714161	9.7939743286692309	-0.0798175335340546	-0.2490875312982012	0.1945920373446899	
+5.9719999999999995	0.0616657925305195	0.0353202754940341	9.8013122515189881	0.1645213832955328	0.1454829111334915	0.0665030085330075	
+5.9729999999999999	0.0724102608076484	0.0372611564322255	9.7927924174967718	-0.0556828063327532	0.0805012820044090	-0.2195095869631494	
+5.9740000000000002	0.0509784326579069	0.0068558240125452	9.8068908093500262	-0.1133533583482637	-0.0029841946001580	0.2813128801254140	
+5.9749999999999996	0.0415745119910952	0.0198842462703941	9.8045006212710142	0.1528303374898478	0.1516097461977090	-0.0895172426551890	
+5.9760000000000000	0.0601016159020067	0.0160879788237847	9.7946824581864007	-0.2026462403462364	-0.0895256064815451	-0.1157182593698536	
+5.9770000000000003	0.0608889483861472	0.0283812221961853	9.7907377904610549	0.2983528306339799	-0.0229913003855406	0.0838369727353068	
+5.9779999999999998	0.0522228342450071	0.0318127244811208	9.8060598996373045	0.0776555514648060	0.2091668341622083	-0.1587632805655029	
+5.9790000000000001	0.0491912799894014	0.0304920066832531	9.8058251673680985	0.2206793810877234	0.0324050866340907	0.2614919001854191	
+5.9799999999999995	0.0525756120954022	0.0080499473437471	9.8006825494586387	0.3283469733499332	-0.0585580597647407	-0.0368525237175009	
+5.9809999999999999	0.0591823090414596	0.0121571597461673	9.8006567426197453	0.1519365910491289	0.1753068778263660	0.0219231768644532	
+5.9820000000000002	0.0635569863950183	0.0287488697515790	9.7832975605881298	-0.1452033627780815	0.2840764481292953	0.1435786349656420	
+5.9829999999999997	0.0459025235079631	0.0179694782334238	9.7959274141732777	0.0415636115618510	0.2745297634229212	0.0581048425243296	
+5.9840000000000000	0.0422988686396547	0.0367444531886476	9.7978414990977605	0.2438673296702862	-0.2229594920499113	-0.0227298390117617	
+5.9850000000000003	0.0622310079733502	0.0092524744758284	9.7962724322551153	0.1737316598530070	0.0054980993095901	0.2049510816268972	
+5.9859999999999998	0.0608940050222149	0.0151460036442788	9.7910594827656539	-0.0348014471659147	0.1134138605652097	0.0499723956793611	
+5.9870000000000001	0.0822057858572428	0.0137940203282641	9.7990646459309509	-0.1422171020969882	-0.1716323555132315	0.1235487804791909	
+5.9879999999999995	0.0351062388574038	0.0523773335445454	9.8152059987596871	-0.0763600343251015	-0.0032531372910828	-0.1240534064695688	
+5.9889999999999999	0.0544622562968301	0.0440811108259592	9.8059719385161941	0.0375212742494560	0.0587011470339566	0.1614773259967537	
+5.9900000000000002	0.0680061959975035	0.0463556425120799	9.8044294118778890	-0.0886846521820241	-0.1978610691141347	0.1243350483742588	
+5.9909999999999997	0.0442246224953564	0.0200732982908159	9.7822356882735875	0.1303496351571954	0.1082475703212219	0.3033642952158485	
+5.9920000000000000	0.0728422326477879	0.0582403472349856	9.8023715495212969	0.0862164928873461	-0.0867133399593496	-0.1042448388651475	
+5.9930000000000003	0.0698218598947639	0.0100420643756210	9.8042135771882695	-0.0473206052485410	0.0631376170486143	0.1593384736889191	
+5.9939999999999998	0.0622431188877887	0.0189966239457677	9.7881875349019918	-0.0996166748149698	-0.1132966752290150	-0.0324488921138300	
+5.9950000000000001	0.0529678517593203	0.0147200397172539	9.8036343831230113	0.1986071174391489	-0.0207646163105617	-0.0129351632995055	
+5.9959999999999996	0.0522684384562457	0.0327037897425001	9.7928500567272128	-0.0168404519188627	0.2579801417543858	-0.0129105793227103	
+5.9969999999999999	0.0612166568659455	0.0359343049649064	9.7882190279844412	0.2011390328356339	-0.0725780127001639	-0.0067290374889596	
+5.9980000000000002	0.0725641917514791	0.0187511517331435	9.7923378308800633	0.2557386945846677	-0.2538726144629979	0.1752332390154829	
+5.9989999999999997	0.0655181146501054	0.0332538345631420	9.7962241878398792	0.1965470514843493	0.0617974114858310	0.2679608064616533	
+6.0000000000000000	0.0670727586862730	0.0162585415118917	9.7683751706204252	-0.0808024456177032	0.0683251272024979	0.0482147548578411	
+6.0010000000000003	0.0568184214249567	0.0184201624949614	9.7960955864075512	0.1395738180536713	-0.1121682109202840	0.0332135520927219	
+6.0019999999999998	0.0589859276722605	0.0402830263215757	9.7979201345696261	0.1600036840188659	0.0911761705400588	-0.0828514037878016	
+6.0030000000000001	0.0523667859803104	0.0173657028568063	9.7939666628591855	-0.0663243662240808	0.1677007416405660	0.3111576283450393	
+6.0039999999999996	0.0628545537326009	0.0132353339257801	9.7891575086150251	0.1205191462238816	0.2399155288449058	0.1146709569973051	
+6.0049999999999999	0.0328979047343192	0.0150566851606356	9.8031363194614336	0.3008324358470187	0.0629064415346549	0.1833853218273430	
diff --git a/src/test/data/IMU/data_pure_translation.txt b/src/test/data/IMU/data_pure_translation.txt
new file mode 100644
index 0000000000000000000000000000000000000000..4337ef93ad5e9de7f00e240a95c1e3cb6e00b39d
--- /dev/null
+++ b/src/test/data/IMU/data_pure_translation.txt
@@ -0,0 +1,10002 @@
+0	0	0	1	0	0	0	1	2	2	
+0	0	0	9.806	0	0	0	
+0.001	-0.001	-0.00799999	9.798	0	0	0	
+0.002	-0.002	-0.016	9.79	0	0	0	
+0.003	-0.003	-0.0239999	9.782	0	0	0	
+0.004	-0.00399999	-0.0319997	9.774	0	0	0	
+0.005	-0.00499998	-0.0399993	9.766	0	0	0	
+0.006	-0.00599996	-0.0479988	9.758	0	0	0	
+0.007	-0.00699994	-0.0559982	9.75	0	0	0	
+0.008	-0.00799991	-0.0639973	9.742	0	0	0	
+0.009	-0.00899988	-0.0719961	9.734	0	0	0	
+0.01	-0.00999983	-0.0799947	9.72601	0	0	0	
+0.011	-0.0109998	-0.0879929	9.71801	0	0	0	
+0.012	-0.0119997	-0.0959908	9.71001	0	0	0	
+0.013	-0.0129996	-0.103988	9.70201	0	0	0	
+0.014	-0.0139995	-0.111985	9.69401	0	0	0	
+0.015	-0.0149994	-0.119982	9.68602	0	0	0	
+0.016	-0.0159993	-0.127978	9.67802	0	0	0	
+0.017	-0.0169992	-0.135974	9.67003	0	0	0	
+0.018	-0.017999	-0.143969	9.66203	0	0	0	
+0.019	-0.0189989	-0.151963	9.65404	0	0	0	
+0.02	-0.0199987	-0.159957	9.64604	0	0	0	
+0.021	-0.0209985	-0.167951	9.63805	0	0	0	
+0.022	-0.0219982	-0.175943	9.63006	0	0	0	
+0.023	-0.022998	-0.183935	9.62206	0	0	0	
+0.024	-0.0239977	-0.191926	9.61407	0	0	0	
+0.025	-0.0249974	-0.199917	9.60608	0	0	0	
+0.026	-0.0259971	-0.207906	9.59809	0	0	0	
+0.027	-0.0269967	-0.215895	9.5901	0	0	0	
+0.028	-0.0279963	-0.223883	9.58212	0	0	0	
+0.029	-0.0289959	-0.23187	9.57413	0	0	0	
+0.03	-0.0299955	-0.239856	9.56614	0	0	0	
+0.031	-0.030995	-0.247841	9.55816	0	0	0	
+0.032	-0.0319945	-0.255825	9.55017	0	0	0	
+0.033	-0.032994	-0.263808	9.54219	0	0	0	
+0.034	-0.0339934	-0.27179	9.53421	0	0	0	
+0.035	-0.0349929	-0.279771	9.52623	0	0	0	
+0.036	-0.0359922	-0.287751	9.51825	0	0	0	
+0.037	-0.0369916	-0.29573	9.51027	0	0	0	
+0.038	-0.0379909	-0.303707	9.50229	0	0	0	
+0.039	-0.0389901	-0.311684	9.49432	0	0	0	
+0.04	-0.0399893	-0.319659	9.48634	0	0	0	
+0.041	-0.0409885	-0.327633	9.47837	0	0	0	
+0.042	-0.0419877	-0.335605	9.47039	0	0	0	
+0.043	-0.0429868	-0.343576	9.46242	0	0	0	
+0.044	-0.0439858	-0.351546	9.45445	0	0	0	
+0.045	-0.0449848	-0.359514	9.44649	0	0	0	
+0.046	-0.0459838	-0.367481	9.43852	0	0	0	
+0.047	-0.0469827	-0.375447	9.43055	0	0	0	
+0.048	-0.0479816	-0.38341	9.42259	0	0	0	
+0.049	-0.0489804	-0.391373	9.41463	0	0	0	
+0.05	-0.0499792	-0.399334	9.40667	0	0	0	
+0.051	-0.0509779	-0.407293	9.39871	0	0	0	
+0.052	-0.0519766	-0.41525	9.39075	0	0	0	
+0.053	-0.0529752	-0.423206	9.38279	0	0	0	
+0.054	-0.0539738	-0.431161	9.37484	0	0	0	
+0.055	-0.0549723	-0.439113	9.36689	0	0	0	
+0.056	-0.0559707	-0.447064	9.35894	0	0	0	
+0.057	-0.0569691	-0.455013	9.35099	0	0	0	
+0.058	-0.0579675	-0.46296	9.34304	0	0	0	
+0.059	-0.0589658	-0.470905	9.33509	0	0	0	
+0.06	-0.059964	-0.478849	9.32715	0	0	0	
+0.061	-0.0609622	-0.48679	9.31921	0	0	0	
+0.062	-0.0619603	-0.49473	9.31127	0	0	0	
+0.063	-0.0629583	-0.502667	9.30333	0	0	0	
+0.064	-0.0639563	-0.510603	9.2954	0	0	0	
+0.065	-0.0649542	-0.518537	9.28746	0	0	0	
+0.066	-0.0659521	-0.526468	9.27953	0	0	0	
+0.067	-0.0669499	-0.534397	9.2716	0	0	0	
+0.068	-0.0679476	-0.542325	9.26368	0	0	0	
+0.069	-0.0689453	-0.55025	9.25575	0	0	0	
+0.07	-0.0699428	-0.558172	9.24783	0	0	0	
+0.071	-0.0709404	-0.566093	9.23991	0	0	0	
+0.072	-0.0719378	-0.574011	9.23199	0	0	0	
+0.073	-0.0729352	-0.581927	9.22407	0	0	0	
+0.074	-0.0739325	-0.589841	9.21616	0	0	0	
+0.075	-0.0749297	-0.597753	9.20825	0	0	0	
+0.076	-0.0759269	-0.605661	9.20034	0	0	0	
+0.077	-0.0769239	-0.613568	9.19243	0	0	0	
+0.078	-0.0779209	-0.621472	9.18453	0	0	0	
+0.079	-0.0789179	-0.629374	9.17663	0	0	0	
+0.08	-0.0799147	-0.637273	9.16873	0	0	0	
+0.081	-0.0809115	-0.645169	9.16083	0	0	0	
+0.082	-0.0819081	-0.653063	9.15294	0	0	0	
+0.083	-0.0829047	-0.660955	9.14505	0	0	0	
+0.084	-0.0839013	-0.668843	9.13716	0	0	0	
+0.085	-0.0848977	-0.676729	9.12927	0	0	0	
+0.086	-0.085894	-0.684613	9.12139	0	0	0	
+0.087	-0.0868903	-0.692493	9.11351	0	0	0	
+0.088	-0.0878865	-0.700371	9.10563	0	0	0	
+0.089	-0.0888826	-0.708246	9.09775	0	0	0	
+0.09	-0.0898785	-0.716118	9.08988	0	0	0	
+0.091	-0.0908745	-0.723988	9.08201	0	0	0	
+0.092	-0.0918703	-0.731854	9.07415	0	0	0	
+0.093	-0.092866	-0.739718	9.06628	0	0	0	
+0.094	-0.0938616	-0.747578	9.05842	0	0	0	
+0.095	-0.0948572	-0.755436	9.05056	0	0	0	
+0.096	-0.0958526	-0.76329	9.04271	0	0	0	
+0.097	-0.096848	-0.771142	9.03486	0	0	0	
+0.098	-0.0978432	-0.77899	9.02701	0	0	0	
+0.099	-0.0988384	-0.786835	9.01916	0	0	0	
+0.1	-0.0998334	-0.794677	9.01132	0	0	0	
+0.101	-0.100828	-0.802516	9.00348	0	0	0	
+0.102	-0.101823	-0.810352	8.99565	0	0	0	
+0.103	-0.102818	-0.818184	8.98782	0	0	0	
+0.104	-0.103813	-0.826014	8.97999	0	0	0	
+0.105	-0.104807	-0.83384	8.97216	0	0	0	
+0.106	-0.105802	-0.841662	8.96434	0	0	0	
+0.107	-0.106796	-0.849481	8.95652	0	0	0	
+0.108	-0.10779	-0.857297	8.9487	0	0	0	
+0.109	-0.108784	-0.86511	8.94089	0	0	0	
+0.11	-0.109778	-0.872918	8.93308	0	0	0	
+0.111	-0.110772	-0.880724	8.92528	0	0	0	
+0.112	-0.111766	-0.888526	8.91747	0	0	0	
+0.113	-0.11276	-0.896324	8.90968	0	0	0	
+0.114	-0.113753	-0.904119	8.90188	0	0	0	
+0.115	-0.114747	-0.91191	8.89409	0	0	0	
+0.116	-0.11574	-0.919698	8.8863	0	0	0	
+0.117	-0.116733	-0.927481	8.87852	0	0	0	
+0.118	-0.117726	-0.935262	8.87074	0	0	0	
+0.119	-0.118719	-0.943038	8.86296	0	0	0	
+0.12	-0.119712	-0.950811	8.85519	0	0	0	
+0.121	-0.120705	-0.958579	8.84742	0	0	0	
+0.122	-0.121698	-0.966344	8.83966	0	0	0	
+0.123	-0.12269	-0.974105	8.83189	0	0	0	
+0.124	-0.123682	-0.981863	8.82414	0	0	0	
+0.125	-0.124675	-0.989616	8.81638	0	0	0	
+0.126	-0.125667	-0.997365	8.80863	0	0	0	
+0.127	-0.126659	-1.00511	8.80089	0	0	0	
+0.128	-0.127651	-1.01285	8.79315	0	0	0	
+0.129	-0.128643	-1.02059	8.78541	0	0	0	
+0.13	-0.129634	-1.02832	8.77768	0	0	0	
+0.131	-0.130626	-1.03605	8.76995	0	0	0	
+0.132	-0.131617	-1.04378	8.76222	0	0	0	
+0.133	-0.132608	-1.0515	8.7545	0	0	0	
+0.134	-0.133599	-1.05921	8.74679	0	0	0	
+0.135	-0.13459	-1.06693	8.73907	0	0	0	
+0.136	-0.135581	-1.07463	8.73137	0	0	0	
+0.137	-0.136572	-1.08234	8.72366	0	0	0	
+0.138	-0.137562	-1.09004	8.71596	0	0	0	
+0.139	-0.138553	-1.09773	8.70827	0	0	0	
+0.14	-0.139543	-1.10542	8.70058	0	0	0	
+0.141	-0.140533	-1.11311	8.69289	0	0	0	
+0.142	-0.141523	-1.12079	8.68521	0	0	0	
+0.143	-0.142513	-1.12847	8.67753	0	0	0	
+0.144	-0.143503	-1.13614	8.66986	0	0	0	
+0.145	-0.144492	-1.14381	8.66219	0	0	0	
+0.146	-0.145482	-1.15147	8.65453	0	0	0	
+0.147	-0.146471	-1.15913	8.64687	0	0	0	
+0.148	-0.14746	-1.16679	8.63921	0	0	0	
+0.149	-0.148449	-1.17444	8.63156	0	0	0	
+0.15	-0.149438	-1.18208	8.62392	0	0	0	
+0.151	-0.150427	-1.18972	8.61628	0	0	0	
+0.152	-0.151415	-1.19736	8.60864	0	0	0	
+0.153	-0.152404	-1.20499	8.60101	0	0	0	
+0.154	-0.153392	-1.21261	8.59339	0	0	0	
+0.155	-0.15438	-1.22023	8.58577	0	0	0	
+0.156	-0.155368	-1.22785	8.57815	0	0	0	
+0.157	-0.156356	-1.23546	8.57054	0	0	0	
+0.158	-0.157343	-1.24307	8.56293	0	0	0	
+0.159	-0.158331	-1.25067	8.55533	0	0	0	
+0.16	-0.159318	-1.25827	8.54773	0	0	0	
+0.161	-0.160305	-1.26586	8.54014	0	0	0	
+0.162	-0.161292	-1.27344	8.53256	0	0	0	
+0.163	-0.162279	-1.28103	8.52497	0	0	0	
+0.164	-0.163266	-1.2886	8.5174	0	0	0	
+0.165	-0.164252	-1.29617	8.50983	0	0	0	
+0.166	-0.165239	-1.30374	8.50226	0	0	0	
+0.167	-0.166225	-1.3113	8.4947	0	0	0	
+0.168	-0.167211	-1.31885	8.48715	0	0	0	
+0.169	-0.168197	-1.3264	8.4796	0	0	0	
+0.17	-0.169182	-1.33395	8.47205	0	0	0	
+0.171	-0.170168	-1.34149	8.46451	0	0	0	
+0.172	-0.171153	-1.34902	8.45698	0	0	0	
+0.173	-0.172138	-1.35655	8.44945	0	0	0	
+0.174	-0.173123	-1.36407	8.44193	0	0	0	
+0.175	-0.174108	-1.37159	8.43441	0	0	0	
+0.176	-0.175093	-1.3791	8.4269	0	0	0	
+0.177	-0.176077	-1.38661	8.41939	0	0	0	
+0.178	-0.177062	-1.39411	8.41189	0	0	0	
+0.179	-0.178046	-1.40161	8.40439	0	0	0	
+0.18	-0.17903	-1.4091	8.3969	0	0	0	
+0.181	-0.180013	-1.41658	8.38942	0	0	0	
+0.182	-0.180997	-1.42406	8.38194	0	0	0	
+0.183	-0.18198	-1.43153	8.37447	0	0	0	
+0.184	-0.182964	-1.439	8.367	0	0	0	
+0.185	-0.183947	-1.44646	8.35954	0	0	0	
+0.186	-0.184929	-1.45392	8.35208	0	0	0	
+0.187	-0.185912	-1.46137	8.34463	0	0	0	
+0.188	-0.186895	-1.46881	8.33719	0	0	0	
+0.189	-0.187877	-1.47625	8.32975	0	0	0	
+0.19	-0.188859	-1.48368	8.32232	0	0	0	
+0.191	-0.189841	-1.49111	8.31489	0	0	0	
+0.192	-0.190823	-1.49853	8.30747	0	0	0	
+0.193	-0.191804	-1.50594	8.30006	0	0	0	
+0.194	-0.192785	-1.51335	8.29265	0	0	0	
+0.195	-0.193767	-1.52075	8.28525	0	0	0	
+0.196	-0.194747	-1.52815	8.27785	0	0	0	
+0.197	-0.195728	-1.53554	8.27046	0	0	0	
+0.198	-0.196709	-1.54292	8.26308	0	0	0	
+0.199	-0.197689	-1.5503	8.2557	0	0	0	
+0.2	-0.198669	-1.55767	8.24833	0	0	0	
+0.201	-0.199649	-1.56504	8.24096	0	0	0	
+0.202	-0.200629	-1.5724	8.2336	0	0	0	
+0.203	-0.201609	-1.57975	8.22625	0	0	0	
+0.204	-0.202588	-1.5871	8.2189	0	0	0	
+0.205	-0.203567	-1.59444	8.21156	0	0	0	
+0.206	-0.204546	-1.60177	8.20423	0	0	0	
+0.207	-0.205525	-1.6091	8.1969	0	0	0	
+0.208	-0.206503	-1.61642	8.18958	0	0	0	
+0.209	-0.207482	-1.62373	8.18227	0	0	0	
+0.21	-0.20846	-1.63104	8.17496	0	0	0	
+0.211	-0.209438	-1.63834	8.16766	0	0	0	
+0.212	-0.210416	-1.64564	8.16036	0	0	0	
+0.213	-0.211393	-1.65293	8.15307	0	0	0	
+0.214	-0.21237	-1.66021	8.14579	0	0	0	
+0.215	-0.213347	-1.66748	8.13852	0	0	0	
+0.216	-0.214324	-1.67475	8.13125	0	0	0	
+0.217	-0.215301	-1.68201	8.12399	0	0	0	
+0.218	-0.216277	-1.68927	8.11673	0	0	0	
+0.219	-0.217254	-1.69652	8.10948	0	0	0	
+0.22	-0.21823	-1.70376	8.10224	0	0	0	
+0.221	-0.219205	-1.71099	8.09501	0	0	0	
+0.222	-0.220181	-1.71822	8.08778	0	0	0	
+0.223	-0.221156	-1.72544	8.08056	0	0	0	
+0.224	-0.222131	-1.73266	8.07334	0	0	0	
+0.225	-0.223106	-1.73986	8.06614	0	0	0	
+0.226	-0.224081	-1.74706	8.05894	0	0	0	
+0.227	-0.225056	-1.75426	8.05174	0	0	0	
+0.228	-0.22603	-1.76144	8.04456	0	0	0	
+0.229	-0.227004	-1.76862	8.03738	0	0	0	
+0.23	-0.227978	-1.77579	8.03021	0	0	0	
+0.231	-0.228951	-1.78296	8.02304	0	0	0	
+0.232	-0.229924	-1.79012	8.01588	0	0	0	
+0.233	-0.230897	-1.79727	8.00873	0	0	0	
+0.234	-0.23187	-1.80441	8.00159	0	0	0	
+0.235	-0.232843	-1.81155	7.99445	0	0	0	
+0.236	-0.233815	-1.81867	7.98733	0	0	0	
+0.237	-0.234788	-1.8258	7.9802	0	0	0	
+0.238	-0.235759	-1.83291	7.97309	0	0	0	
+0.239	-0.236731	-1.84002	7.96598	0	0	0	
+0.24	-0.237703	-1.84712	7.95888	0	0	0	
+0.241	-0.238674	-1.85421	7.95179	0	0	0	
+0.242	-0.239645	-1.86129	7.94471	0	0	0	
+0.243	-0.240616	-1.86837	7.93763	0	0	0	
+0.244	-0.241586	-1.87544	7.93056	0	0	0	
+0.245	-0.242556	-1.8825	7.9235	0	0	0	
+0.246	-0.243526	-1.88956	7.91644	0	0	0	
+0.247	-0.244496	-1.89661	7.90939	0	0	0	
+0.248	-0.245466	-1.90365	7.90235	0	0	0	
+0.249	-0.246435	-1.91068	7.89532	0	0	0	
+0.25	-0.247404	-1.9177	7.8883	0	0	0	
+0.251	-0.248373	-1.92472	7.88128	0	0	0	
+0.252	-0.249341	-1.93173	7.87427	0	0	0	
+0.253	-0.25031	-1.93873	7.86727	0	0	0	
+0.254	-0.251278	-1.94572	7.86028	0	0	0	
+0.255	-0.252245	-1.95271	7.85329	0	0	0	
+0.256	-0.253213	-1.95969	7.84631	0	0	0	
+0.257	-0.25418	-1.96666	7.83934	0	0	0	
+0.258	-0.255147	-1.97362	7.83238	0	0	0	
+0.259	-0.256114	-1.98057	7.82543	0	0	0	
+0.26	-0.257081	-1.98752	7.81848	0	0	0	
+0.261	-0.258047	-1.99446	7.81154	0	0	0	
+0.262	-0.259013	-2.00139	7.80461	0	0	0	
+0.263	-0.259979	-2.00831	7.79769	0	0	0	
+0.264	-0.260944	-2.01523	7.79077	0	0	0	
+0.265	-0.261909	-2.02213	7.78387	0	0	0	
+0.266	-0.262874	-2.02903	7.77697	0	0	0	
+0.267	-0.263839	-2.03592	7.77008	0	0	0	
+0.268	-0.264803	-2.0428	7.7632	0	0	0	
+0.269	-0.265768	-2.04968	7.75632	0	0	0	
+0.27	-0.266731	-2.05654	7.74946	0	0	0	
+0.271	-0.267695	-2.0634	7.7426	0	0	0	
+0.272	-0.268658	-2.07025	7.73575	0	0	0	
+0.273	-0.269622	-2.07709	7.72891	0	0	0	
+0.274	-0.270584	-2.08392	7.72208	0	0	0	
+0.275	-0.271547	-2.09075	7.71525	0	0	0	
+0.276	-0.272509	-2.09756	7.70844	0	0	0	
+0.277	-0.273471	-2.10437	7.70163	0	0	0	
+0.278	-0.274433	-2.11117	7.69483	0	0	0	
+0.279	-0.275394	-2.11796	7.68804	0	0	0	
+0.28	-0.276356	-2.12474	7.68126	0	0	0	
+0.281	-0.277317	-2.13152	7.67448	0	0	0	
+0.282	-0.278277	-2.13828	7.66772	0	0	0	
+0.283	-0.279238	-2.14504	7.66096	0	0	0	
+0.284	-0.280198	-2.15179	7.65421	0	0	0	
+0.285	-0.281157	-2.15853	7.64747	0	0	0	
+0.286	-0.282117	-2.16526	7.64074	0	0	0	
+0.287	-0.283076	-2.17198	7.63402	0	0	0	
+0.288	-0.284035	-2.17869	7.62731	0	0	0	
+0.289	-0.284994	-2.1854	7.6206	0	0	0	
+0.29	-0.285952	-2.1921	7.6139	0	0	0	
+0.291	-0.28691	-2.19878	7.60722	0	0	0	
+0.292	-0.287868	-2.20546	7.60054	0	0	0	
+0.293	-0.288826	-2.21213	7.59387	0	0	0	
+0.294	-0.289783	-2.21879	7.58721	0	0	0	
+0.295	-0.29074	-2.22544	7.58056	0	0	0	
+0.296	-0.291697	-2.23209	7.57391	0	0	0	
+0.297	-0.292653	-2.23872	7.56728	0	0	0	
+0.298	-0.293609	-2.24535	7.56065	0	0	0	
+0.299	-0.294565	-2.25196	7.55404	0	0	0	
+0.3	-0.29552	-2.25857	7.54743	0	0	0	
+0.301	-0.296475	-2.26517	7.54083	0	0	0	
+0.302	-0.29743	-2.27176	7.53424	0	0	0	
+0.303	-0.298385	-2.27834	7.52766	0	0	0	
+0.304	-0.299339	-2.28491	7.52109	0	0	0	
+0.305	-0.300293	-2.29147	7.51453	0	0	0	
+0.306	-0.301247	-2.29802	7.50798	0	0	0	
+0.307	-0.3022	-2.30457	7.50143	0	0	0	
+0.308	-0.303153	-2.3111	7.4949	0	0	0	
+0.309	-0.304106	-2.31762	7.48838	0	0	0	
+0.31	-0.305059	-2.32414	7.48186	0	0	0	
+0.311	-0.306011	-2.33065	7.47535	0	0	0	
+0.312	-0.306963	-2.33714	7.46886	0	0	0	
+0.313	-0.307914	-2.34363	7.46237	0	0	0	
+0.314	-0.308866	-2.35011	7.45589	0	0	0	
+0.315	-0.309816	-2.35658	7.44942	0	0	0	
+0.316	-0.310767	-2.36304	7.44296	0	0	0	
+0.317	-0.311717	-2.36949	7.43651	0	0	0	
+0.318	-0.312667	-2.37593	7.43007	0	0	0	
+0.319	-0.313617	-2.38236	7.42364	0	0	0	
+0.32	-0.314567	-2.38878	7.41722	0	0	0	
+0.321	-0.315516	-2.39519	7.41081	0	0	0	
+0.322	-0.316464	-2.4016	7.4044	0	0	0	
+0.323	-0.317413	-2.40799	7.39801	0	0	0	
+0.324	-0.318361	-2.41437	7.39163	0	0	0	
+0.325	-0.319309	-2.42075	7.38525	0	0	0	
+0.326	-0.320256	-2.42711	7.37889	0	0	0	
+0.327	-0.321203	-2.43346	7.37254	0	0	0	
+0.328	-0.32215	-2.43981	7.36619	0	0	0	
+0.329	-0.323097	-2.44614	7.35986	0	0	0	
+0.33	-0.324043	-2.45247	7.35353	0	0	0	
+0.331	-0.324989	-2.45878	7.34722	0	0	0	
+0.332	-0.325934	-2.46509	7.34091	0	0	0	
+0.333	-0.32688	-2.47138	7.33462	0	0	0	
+0.334	-0.327825	-2.47767	7.32833	0	0	0	
+0.335	-0.328769	-2.48394	7.32206	0	0	0	
+0.336	-0.329713	-2.49021	7.31579	0	0	0	
+0.337	-0.330657	-2.49647	7.30953	0	0	0	
+0.338	-0.331601	-2.50271	7.30329	0	0	0	
+0.339	-0.332544	-2.50895	7.29705	0	0	0	
+0.34	-0.333487	-2.51517	7.29083	0	0	0	
+0.341	-0.33443	-2.52139	7.28461	0	0	0	
+0.342	-0.335372	-2.52759	7.27841	0	0	0	
+0.343	-0.336314	-2.53379	7.27221	0	0	0	
+0.344	-0.337255	-2.53997	7.26603	0	0	0	
+0.345	-0.338197	-2.54615	7.25985	0	0	0	
+0.346	-0.339138	-2.55231	7.25369	0	0	0	
+0.347	-0.340078	-2.55847	7.24753	0	0	0	
+0.348	-0.341018	-2.56461	7.24139	0	0	0	
+0.349	-0.341958	-2.57075	7.23525	0	0	0	
+0.35	-0.342898	-2.57687	7.22913	0	0	0	
+0.351	-0.343837	-2.58298	7.22302	0	0	0	
+0.352	-0.344776	-2.58909	7.21691	0	0	0	
+0.353	-0.345714	-2.59518	7.21082	0	0	0	
+0.354	-0.346653	-2.60126	7.20474	0	0	0	
+0.355	-0.34759	-2.60734	7.19866	0	0	0	
+0.356	-0.348528	-2.6134	7.1926	0	0	0	
+0.357	-0.349465	-2.61945	7.18655	0	0	0	
+0.358	-0.350402	-2.62549	7.18051	0	0	0	
+0.359	-0.351338	-2.63152	7.17448	0	0	0	
+0.36	-0.352274	-2.63754	7.16846	0	0	0	
+0.361	-0.35321	-2.64355	7.16245	0	0	0	
+0.362	-0.354145	-2.64955	7.15645	0	0	0	
+0.363	-0.35508	-2.65553	7.15047	0	0	0	
+0.364	-0.356015	-2.66151	7.14449	0	0	0	
+0.365	-0.356949	-2.66748	7.13852	0	0	0	
+0.366	-0.357883	-2.67343	7.13257	0	0	0	
+0.367	-0.358817	-2.67938	7.12662	0	0	0	
+0.368	-0.35975	-2.68531	7.12069	0	0	0	
+0.369	-0.360683	-2.69124	7.11476	0	0	0	
+0.37	-0.361615	-2.69715	7.10885	0	0	0	
+0.371	-0.362548	-2.70305	7.10295	0	0	0	
+0.372	-0.363479	-2.70895	7.09705	0	0	0	
+0.373	-0.364411	-2.71483	7.09117	0	0	0	
+0.374	-0.365342	-2.7207	7.0853	0	0	0	
+0.375	-0.366273	-2.72656	7.07944	0	0	0	
+0.376	-0.367203	-2.7324	7.0736	0	0	0	
+0.377	-0.368133	-2.73824	7.06776	0	0	0	
+0.378	-0.369062	-2.74407	7.06193	0	0	0	
+0.379	-0.369992	-2.74988	7.05612	0	0	0	
+0.38	-0.37092	-2.75569	7.05031	0	0	0	
+0.381	-0.371849	-2.76148	7.04452	0	0	0	
+0.382	-0.372777	-2.76726	7.03874	0	0	0	
+0.383	-0.373705	-2.77303	7.03297	0	0	0	
+0.384	-0.374632	-2.77879	7.02721	0	0	0	
+0.385	-0.375559	-2.78454	7.02146	0	0	0	
+0.386	-0.376486	-2.79028	7.01572	0	0	0	
+0.387	-0.377412	-2.79601	7.00999	0	0	0	
+0.388	-0.378338	-2.80172	7.00428	0	0	0	
+0.389	-0.379263	-2.80742	6.99858	0	0	0	
+0.39	-0.380188	-2.81312	6.99288	0	0	0	
+0.391	-0.381113	-2.8188	6.9872	0	0	0	
+0.392	-0.382037	-2.82447	6.98153	0	0	0	
+0.393	-0.382961	-2.83013	6.97587	0	0	0	
+0.394	-0.383885	-2.83578	6.97022	0	0	0	
+0.395	-0.384808	-2.84141	6.96459	0	0	0	
+0.396	-0.385731	-2.84704	6.95896	0	0	0	
+0.397	-0.386653	-2.85265	6.95335	0	0	0	
+0.398	-0.387575	-2.85825	6.94775	0	0	0	
+0.399	-0.388497	-2.86384	6.94216	0	0	0	
+0.4	-0.389418	-2.86942	6.93658	0	0	0	
+0.401	-0.390339	-2.87499	6.93101	0	0	0	
+0.402	-0.39126	-2.88055	6.92545	0	0	0	
+0.403	-0.39218	-2.88609	6.91991	0	0	0	
+0.404	-0.393099	-2.89163	6.91437	0	0	0	
+0.405	-0.394019	-2.89715	6.90885	0	0	0	
+0.406	-0.394938	-2.90266	6.90334	0	0	0	
+0.407	-0.395856	-2.90816	6.89784	0	0	0	
+0.408	-0.396774	-2.91364	6.89236	0	0	0	
+0.409	-0.397692	-2.91912	6.88688	0	0	0	
+0.41	-0.398609	-2.92458	6.88142	0	0	0	
+0.411	-0.399526	-2.93004	6.87596	0	0	0	
+0.412	-0.400443	-2.93548	6.87052	0	0	0	
+0.413	-0.401359	-2.9409	6.8651	0	0	0	
+0.414	-0.402275	-2.94632	6.85968	0	0	0	
+0.415	-0.40319	-2.95173	6.85427	0	0	0	
+0.416	-0.404105	-2.95712	6.84888	0	0	0	
+0.417	-0.405019	-2.9625	6.8435	0	0	0	
+0.418	-0.405933	-2.96787	6.83813	0	0	0	
+0.419	-0.406847	-2.97323	6.83277	0	0	0	
+0.42	-0.40776	-2.97857	6.82743	0	0	0	
+0.421	-0.408673	-2.98391	6.82209	0	0	0	
+0.422	-0.409586	-2.98923	6.81677	0	0	0	
+0.423	-0.410498	-2.99454	6.81146	0	0	0	
+0.424	-0.41141	-2.99984	6.80616	0	0	0	
+0.425	-0.412321	-3.00512	6.80088	0	0	0	
+0.426	-0.413232	-3.0104	6.7956	0	0	0	
+0.427	-0.414142	-3.01566	6.79034	0	0	0	
+0.428	-0.415052	-3.02091	6.78509	0	0	0	
+0.429	-0.415962	-3.02614	6.77986	0	0	0	
+0.43	-0.416871	-3.03137	6.77463	0	0	0	
+0.431	-0.41778	-3.03658	6.76942	0	0	0	
+0.432	-0.418688	-3.04178	6.76422	0	0	0	
+0.433	-0.419596	-3.04697	6.75903	0	0	0	
+0.434	-0.420503	-3.05215	6.75385	0	0	0	
+0.435	-0.42141	-3.05732	6.74868	0	0	0	
+0.436	-0.422317	-3.06247	6.74353	0	0	0	
+0.437	-0.423223	-3.06761	6.73839	0	0	0	
+0.438	-0.424129	-3.07274	6.73326	0	0	0	
+0.439	-0.425035	-3.07785	6.72815	0	0	0	
+0.44	-0.425939	-3.08296	6.72304	0	0	0	
+0.441	-0.426844	-3.08805	6.71795	0	0	0	
+0.442	-0.427748	-3.09313	6.71287	0	0	0	
+0.443	-0.428652	-3.09819	6.70781	0	0	0	
+0.444	-0.429555	-3.10325	6.70275	0	0	0	
+0.445	-0.430458	-3.10829	6.69771	0	0	0	
+0.446	-0.43136	-3.11332	6.69268	0	0	0	
+0.447	-0.432262	-3.11833	6.68767	0	0	0	
+0.448	-0.433164	-3.12334	6.68266	0	0	0	
+0.449	-0.434065	-3.12833	6.67767	0	0	0	
+0.45	-0.434966	-3.13331	6.67269	0	0	0	
+0.451	-0.435866	-3.13827	6.66773	0	0	0	
+0.452	-0.436766	-3.14323	6.66277	0	0	0	
+0.453	-0.437665	-3.14817	6.65783	0	0	0	
+0.454	-0.438564	-3.1531	6.6529	0	0	0	
+0.455	-0.439462	-3.15801	6.64799	0	0	0	
+0.456	-0.44036	-3.16292	6.64308	0	0	0	
+0.457	-0.441258	-3.16781	6.63819	0	0	0	
+0.458	-0.442155	-3.17269	6.63331	0	0	0	
+0.459	-0.443052	-3.17755	6.62845	0	0	0	
+0.46	-0.443948	-3.18241	6.62359	0	0	0	
+0.461	-0.444844	-3.18725	6.61875	0	0	0	
+0.462	-0.445739	-3.19207	6.61393	0	0	0	
+0.463	-0.446634	-3.19689	6.60911	0	0	0	
+0.464	-0.447529	-3.20169	6.60431	0	0	0	
+0.465	-0.448423	-3.20648	6.59952	0	0	0	
+0.466	-0.449316	-3.21126	6.59474	0	0	0	
+0.467	-0.45021	-3.21602	6.58998	0	0	0	
+0.468	-0.451102	-3.22077	6.58523	0	0	0	
+0.469	-0.451994	-3.22551	6.58049	0	0	0	
+0.47	-0.452886	-3.23023	6.57577	0	0	0	
+0.471	-0.453778	-3.23494	6.57106	0	0	0	
+0.472	-0.454669	-3.23964	6.56636	0	0	0	
+0.473	-0.455559	-3.24433	6.56167	0	0	0	
+0.474	-0.456449	-3.249	6.557	0	0	0	
+0.475	-0.457338	-3.25366	6.55234	0	0	0	
+0.476	-0.458228	-3.25831	6.54769	0	0	0	
+0.477	-0.459116	-3.26294	6.54306	0	0	0	
+0.478	-0.460004	-3.26756	6.53844	0	0	0	
+0.479	-0.460892	-3.27217	6.53383	0	0	0	
+0.48	-0.461779	-3.27677	6.52923	0	0	0	
+0.481	-0.462666	-3.28135	6.52465	0	0	0	
+0.482	-0.463552	-3.28592	6.52008	0	0	0	
+0.483	-0.464438	-3.29047	6.51553	0	0	0	
+0.484	-0.465323	-3.29501	6.51099	0	0	0	
+0.485	-0.466208	-3.29954	6.50646	0	0	0	
+0.486	-0.467093	-3.30406	6.50194	0	0	0	
+0.487	-0.467977	-3.30856	6.49744	0	0	0	
+0.488	-0.46886	-3.31305	6.49295	0	0	0	
+0.489	-0.469743	-3.31753	6.48847	0	0	0	
+0.49	-0.470626	-3.32199	6.48401	0	0	0	
+0.491	-0.471508	-3.32644	6.47956	0	0	0	
+0.492	-0.47239	-3.33088	6.47512	0	0	0	
+0.493	-0.473271	-3.3353	6.4707	0	0	0	
+0.494	-0.474151	-3.33971	6.46629	0	0	0	
+0.495	-0.475032	-3.3441	6.4619	0	0	0	
+0.496	-0.475911	-3.34849	6.45751	0	0	0	
+0.497	-0.476791	-3.35286	6.45314	0	0	0	
+0.498	-0.477669	-3.35721	6.44879	0	0	0	
+0.499	-0.478548	-3.36155	6.44445	0	0	0	
+0.5	-0.479426	-3.36588	6.44012	0	0	0	
+0.501	-0.480303	-3.3702	6.4358	0	0	0	
+0.502	-0.48118	-3.3745	6.4315	0	0	0	
+0.503	-0.482056	-3.37879	6.42721	0	0	0	
+0.504	-0.482932	-3.38307	6.42293	0	0	0	
+0.505	-0.483807	-3.38733	6.41867	0	0	0	
+0.506	-0.484682	-3.39158	6.41442	0	0	0	
+0.507	-0.485557	-3.39581	6.41019	0	0	0	
+0.508	-0.486431	-3.40003	6.40597	0	0	0	
+0.509	-0.487304	-3.40424	6.40176	0	0	0	
+0.51	-0.488177	-3.40843	6.39757	0	0	0	
+0.511	-0.48905	-3.41261	6.39339	0	0	0	
+0.512	-0.489922	-3.41678	6.38922	0	0	0	
+0.513	-0.490793	-3.42093	6.38507	0	0	0	
+0.514	-0.491664	-3.42507	6.38093	0	0	0	
+0.515	-0.492535	-3.4292	6.3768	0	0	0	
+0.516	-0.493405	-3.43331	6.37269	0	0	0	
+0.517	-0.494274	-3.43741	6.36859	0	0	0	
+0.518	-0.495144	-3.44149	6.36451	0	0	0	
+0.519	-0.496012	-3.44556	6.36044	0	0	0	
+0.52	-0.49688	-3.44962	6.35638	0	0	0	
+0.521	-0.497748	-3.45366	6.35234	0	0	0	
+0.522	-0.498615	-3.45769	6.34831	0	0	0	
+0.523	-0.499481	-3.4617	6.3443	0	0	0	
+0.524	-0.500347	-3.46571	6.34029	0	0	0	
+0.525	-0.501213	-3.46969	6.33631	0	0	0	
+0.526	-0.502078	-3.47367	6.33233	0	0	0	
+0.527	-0.502943	-3.47763	6.32837	0	0	0	
+0.528	-0.503807	-3.48157	6.32443	0	0	0	
+0.529	-0.50467	-3.4855	6.3205	0	0	0	
+0.53	-0.505533	-3.48942	6.31658	0	0	0	
+0.531	-0.506396	-3.49333	6.31267	0	0	0	
+0.532	-0.507258	-3.49722	6.30878	0	0	0	
+0.533	-0.508119	-3.50109	6.30491	0	0	0	
+0.534	-0.508981	-3.50495	6.30105	0	0	0	
+0.535	-0.509841	-3.5088	6.2972	0	0	0	
+0.536	-0.510701	-3.51264	6.29336	0	0	0	
+0.537	-0.511561	-3.51646	6.28954	0	0	0	
+0.538	-0.51242	-3.52026	6.28574	0	0	0	
+0.539	-0.513278	-3.52405	6.28195	0	0	0	
+0.54	-0.514136	-3.52783	6.27817	0	0	0	
+0.541	-0.514993	-3.53159	6.27441	0	0	0	
+0.542	-0.51585	-3.53534	6.27066	0	0	0	
+0.543	-0.516707	-3.53908	6.26692	0	0	0	
+0.544	-0.517563	-3.5428	6.2632	0	0	0	
+0.545	-0.518418	-3.54651	6.25949	0	0	0	
+0.546	-0.519273	-3.5502	6.2558	0	0	0	
+0.547	-0.520127	-3.55388	6.25212	0	0	0	
+0.548	-0.520981	-3.55754	6.24846	0	0	0	
+0.549	-0.521834	-3.56119	6.24481	0	0	0	
+0.55	-0.522687	-3.56483	6.24117	0	0	0	
+0.551	-0.523539	-3.56845	6.23755	0	0	0	
+0.552	-0.524391	-3.57206	6.23394	0	0	0	
+0.553	-0.525242	-3.57565	6.23035	0	0	0	
+0.554	-0.526093	-3.57923	6.22677	0	0	0	
+0.555	-0.526943	-3.58279	6.22321	0	0	0	
+0.556	-0.527793	-3.58634	6.21966	0	0	0	
+0.557	-0.528642	-3.58988	6.21612	0	0	0	
+0.558	-0.529491	-3.5934	6.2126	0	0	0	
+0.559	-0.530339	-3.59691	6.20909	0	0	0	
+0.56	-0.531186	-3.6004	6.2056	0	0	0	
+0.561	-0.532033	-3.60388	6.20212	0	0	0	
+0.562	-0.53288	-3.60734	6.19866	0	0	0	
+0.563	-0.533726	-3.61079	6.19521	0	0	0	
+0.564	-0.534571	-3.61423	6.19177	0	0	0	
+0.565	-0.535416	-3.61765	6.18835	0	0	0	
+0.566	-0.53626	-3.62105	6.18495	0	0	0	
+0.567	-0.537104	-3.62445	6.18155	0	0	0	
+0.568	-0.537947	-3.62782	6.17818	0	0	0	
+0.569	-0.53879	-3.63119	6.17481	0	0	0	
+0.57	-0.539632	-3.63453	6.17147	0	0	0	
+0.571	-0.540474	-3.63787	6.16813	0	0	0	
+0.572	-0.541315	-3.64119	6.16481	0	0	0	
+0.573	-0.542155	-3.64449	6.16151	0	0	0	
+0.574	-0.542995	-3.64778	6.15822	0	0	0	
+0.575	-0.543835	-3.65106	6.15494	0	0	0	
+0.576	-0.544674	-3.65432	6.15168	0	0	0	
+0.577	-0.545512	-3.65756	6.14844	0	0	0	
+0.578	-0.54635	-3.66079	6.14521	0	0	0	
+0.579	-0.547187	-3.66401	6.14199	0	0	0	
+0.58	-0.548024	-3.66721	6.13879	0	0	0	
+0.581	-0.54886	-3.6704	6.1356	0	0	0	
+0.582	-0.549696	-3.67357	6.13243	0	0	0	
+0.583	-0.550531	-3.67673	6.12927	0	0	0	
+0.584	-0.551365	-3.67987	6.12613	0	0	0	
+0.585	-0.552199	-3.683	6.123	0	0	0	
+0.586	-0.553033	-3.68612	6.11988	0	0	0	
+0.587	-0.553866	-3.68922	6.11678	0	0	0	
+0.588	-0.554698	-3.6923	6.1137	0	0	0	
+0.589	-0.55553	-3.69537	6.11063	0	0	0	
+0.59	-0.556361	-3.69842	6.10758	0	0	0	
+0.591	-0.557192	-3.70146	6.10454	0	0	0	
+0.592	-0.558022	-3.70449	6.10151	0	0	0	
+0.593	-0.558851	-3.7075	6.0985	0	0	0	
+0.594	-0.55968	-3.7105	6.0955	0	0	0	
+0.595	-0.560509	-3.71348	6.09252	0	0	0	
+0.596	-0.561337	-3.71644	6.08956	0	0	0	
+0.597	-0.562164	-3.71939	6.08661	0	0	0	
+0.598	-0.562991	-3.72233	6.08367	0	0	0	
+0.599	-0.563817	-3.72525	6.08075	0	0	0	
+0.6	-0.564642	-3.72816	6.07784	0	0	0	
+0.601	-0.565468	-3.73105	6.07495	0	0	0	
+0.602	-0.566292	-3.73392	6.07208	0	0	0	
+0.603	-0.567116	-3.73679	6.06921	0	0	0	
+0.604	-0.567939	-3.73963	6.06637	0	0	0	
+0.605	-0.568762	-3.74246	6.06354	0	0	0	
+0.606	-0.569584	-3.74528	6.06072	0	0	0	
+0.607	-0.570406	-3.74808	6.05792	0	0	0	
+0.608	-0.571227	-3.75087	6.05513	0	0	0	
+0.609	-0.572048	-3.75364	6.05236	0	0	0	
+0.61	-0.572867	-3.7564	6.0496	0	0	0	
+0.611	-0.573687	-3.75914	6.04686	0	0	0	
+0.612	-0.574506	-3.76187	6.04413	0	0	0	
+0.613	-0.575324	-3.76458	6.04142	0	0	0	
+0.614	-0.576141	-3.76727	6.03873	0	0	0	
+0.615	-0.576959	-3.76996	6.03604	0	0	0	
+0.616	-0.577775	-3.77262	6.03338	0	0	0	
+0.617	-0.578591	-3.77527	6.03073	0	0	0	
+0.618	-0.579406	-3.77791	6.02809	0	0	0	
+0.619	-0.580221	-3.78053	6.02547	0	0	0	
+0.62	-0.581035	-3.78314	6.02286	0	0	0	
+0.621	-0.581849	-3.78573	6.02027	0	0	0	
+0.622	-0.582662	-3.7883	6.0177	0	0	0	
+0.623	-0.583474	-3.79086	6.01514	0	0	0	
+0.624	-0.584286	-3.79341	6.01259	0	0	0	
+0.625	-0.585097	-3.79594	6.01006	0	0	0	
+0.626	-0.585908	-3.79845	6.00755	0	0	0	
+0.627	-0.586718	-3.80095	6.00505	0	0	0	
+0.628	-0.587528	-3.80344	6.00256	0	0	0	
+0.629	-0.588336	-3.80591	6.00009	0	0	0	
+0.63	-0.589145	-3.80836	5.99764	0	0	0	
+0.631	-0.589952	-3.8108	5.9952	0	0	0	
+0.632	-0.59076	-3.81322	5.99278	0	0	0	
+0.633	-0.591566	-3.81563	5.99037	0	0	0	
+0.634	-0.592372	-3.81803	5.98797	0	0	0	
+0.635	-0.593178	-3.8204	5.9856	0	0	0	
+0.636	-0.593982	-3.82277	5.98323	0	0	0	
+0.637	-0.594786	-3.82511	5.98089	0	0	0	
+0.638	-0.59559	-3.82745	5.97855	0	0	0	
+0.639	-0.596393	-3.82976	5.97624	0	0	0	
+0.64	-0.597195	-3.83206	5.97394	0	0	0	
+0.641	-0.597997	-3.83435	5.97165	0	0	0	
+0.642	-0.598798	-3.83662	5.96938	0	0	0	
+0.643	-0.599599	-3.83888	5.96712	0	0	0	
+0.644	-0.600399	-3.84112	5.96488	0	0	0	
+0.645	-0.601198	-3.84334	5.96266	0	0	0	
+0.646	-0.601997	-3.84555	5.96045	0	0	0	
+0.647	-0.602795	-3.84774	5.95826	0	0	0	
+0.648	-0.603593	-3.84992	5.95608	0	0	0	
+0.649	-0.60439	-3.85209	5.95391	0	0	0	
+0.65	-0.605186	-3.85423	5.95177	0	0	0	
+0.651	-0.605982	-3.85637	5.94963	0	0	0	
+0.652	-0.606777	-3.85848	5.94752	0	0	0	
+0.653	-0.607572	-3.86058	5.94542	0	0	0	
+0.654	-0.608366	-3.86267	5.94333	0	0	0	
+0.655	-0.609159	-3.86474	5.94126	0	0	0	
+0.656	-0.609952	-3.86679	5.93921	0	0	0	
+0.657	-0.610744	-3.86883	5.93717	0	0	0	
+0.658	-0.611536	-3.87086	5.93514	0	0	0	
+0.659	-0.612327	-3.87287	5.93313	0	0	0	
+0.66	-0.613117	-3.87486	5.93114	0	0	0	
+0.661	-0.613907	-3.87684	5.92916	0	0	0	
+0.662	-0.614696	-3.8788	5.9272	0	0	0	
+0.663	-0.615484	-3.88075	5.92525	0	0	0	
+0.664	-0.616272	-3.88268	5.92332	0	0	0	
+0.665	-0.617059	-3.88459	5.92141	0	0	0	
+0.666	-0.617846	-3.88649	5.91951	0	0	0	
+0.667	-0.618632	-3.88838	5.91762	0	0	0	
+0.668	-0.619417	-3.89025	5.91575	0	0	0	
+0.669	-0.620202	-3.8921	5.9139	0	0	0	
+0.67	-0.620986	-3.89394	5.91206	0	0	0	
+0.671	-0.621769	-3.89576	5.91024	0	0	0	
+0.672	-0.622552	-3.89757	5.90843	0	0	0	
+0.673	-0.623335	-3.89936	5.90664	0	0	0	
+0.674	-0.624116	-3.90113	5.90487	0	0	0	
+0.675	-0.624897	-3.90289	5.90311	0	0	0	
+0.676	-0.625678	-3.90464	5.90136	0	0	0	
+0.677	-0.626457	-3.90637	5.89963	0	0	0	
+0.678	-0.627237	-3.90808	5.89792	0	0	0	
+0.679	-0.628015	-3.90978	5.89622	0	0	0	
+0.68	-0.628793	-3.91146	5.89454	0	0	0	
+0.681	-0.62957	-3.91312	5.89288	0	0	0	
+0.682	-0.630347	-3.91477	5.89123	0	0	0	
+0.683	-0.631123	-3.91641	5.88959	0	0	0	
+0.684	-0.631898	-3.91803	5.88797	0	0	0	
+0.685	-0.632673	-3.91963	5.88637	0	0	0	
+0.686	-0.633447	-3.92122	5.88478	0	0	0	
+0.687	-0.634221	-3.92279	5.88321	0	0	0	
+0.688	-0.634993	-3.92435	5.88165	0	0	0	
+0.689	-0.635766	-3.92589	5.88011	0	0	0	
+0.69	-0.636537	-3.92741	5.87859	0	0	0	
+0.691	-0.637308	-3.92892	5.87708	0	0	0	
+0.692	-0.638078	-3.93042	5.87558	0	0	0	
+0.693	-0.638848	-3.93189	5.87411	0	0	0	
+0.694	-0.639617	-3.93336	5.87264	0	0	0	
+0.695	-0.640385	-3.9348	5.8712	0	0	0	
+0.696	-0.641153	-3.93623	5.86977	0	0	0	
+0.697	-0.64192	-3.93765	5.86835	0	0	0	
+0.698	-0.642687	-3.93905	5.86695	0	0	0	
+0.699	-0.643453	-3.94043	5.86557	0	0	0	
+0.7	-0.644218	-3.9418	5.8642	0	0	0	
+0.701	-0.644982	-3.94315	5.86285	0	0	0	
+0.702	-0.645746	-3.94449	5.86151	0	0	0	
+0.703	-0.646509	-3.94581	5.86019	0	0	0	
+0.704	-0.647272	-3.94711	5.85889	0	0	0	
+0.705	-0.648034	-3.9484	5.8576	0	0	0	
+0.706	-0.648795	-3.94967	5.85633	0	0	0	
+0.707	-0.649556	-3.95093	5.85507	0	0	0	
+0.708	-0.650316	-3.95217	5.85383	0	0	0	
+0.709	-0.651075	-3.9534	5.8526	0	0	0	
+0.71	-0.651834	-3.95461	5.85139	0	0	0	
+0.711	-0.652592	-3.9558	5.8502	0	0	0	
+0.712	-0.653349	-3.95698	5.84902	0	0	0	
+0.713	-0.654106	-3.95814	5.84786	0	0	0	
+0.714	-0.654862	-3.95929	5.84671	0	0	0	
+0.715	-0.655617	-3.96042	5.84558	0	0	0	
+0.716	-0.656372	-3.96153	5.84447	0	0	0	
+0.717	-0.657126	-3.96263	5.84337	0	0	0	
+0.718	-0.65788	-3.96371	5.84229	0	0	0	
+0.719	-0.658633	-3.96478	5.84122	0	0	0	
+0.72	-0.659385	-3.96583	5.84017	0	0	0	
+0.721	-0.660136	-3.96687	5.83913	0	0	0	
+0.722	-0.660887	-3.96789	5.83811	0	0	0	
+0.723	-0.661637	-3.96889	5.83711	0	0	0	
+0.724	-0.662387	-3.96988	5.83612	0	0	0	
+0.725	-0.663135	-3.97085	5.83515	0	0	0	
+0.726	-0.663884	-3.97181	5.83419	0	0	0	
+0.727	-0.664631	-3.97275	5.83325	0	0	0	
+0.728	-0.665378	-3.97367	5.83233	0	0	0	
+0.729	-0.666124	-3.97458	5.83142	0	0	0	
+0.73	-0.66687	-3.97547	5.83053	0	0	0	
+0.731	-0.667614	-3.97635	5.82965	0	0	0	
+0.732	-0.668359	-3.97721	5.82879	0	0	0	
+0.733	-0.669102	-3.97806	5.82794	0	0	0	
+0.734	-0.669845	-3.97888	5.82712	0	0	0	
+0.735	-0.670587	-3.9797	5.8263	0	0	0	
+0.736	-0.671329	-3.98049	5.82551	0	0	0	
+0.737	-0.672069	-3.98128	5.82472	0	0	0	
+0.738	-0.67281	-3.98204	5.82396	0	0	0	
+0.739	-0.673549	-3.98279	5.82321	0	0	0	
+0.74	-0.674288	-3.98352	5.82248	0	0	0	
+0.741	-0.675026	-3.98424	5.82176	0	0	0	
+0.742	-0.675763	-3.98494	5.82106	0	0	0	
+0.743	-0.6765	-3.98563	5.82037	0	0	0	
+0.744	-0.677236	-3.9863	5.8197	0	0	0	
+0.745	-0.677972	-3.98695	5.81905	0	0	0	
+0.746	-0.678707	-3.98759	5.81841	0	0	0	
+0.747	-0.679441	-3.98821	5.81779	0	0	0	
+0.748	-0.680174	-3.98882	5.81718	0	0	0	
+0.749	-0.680907	-3.98941	5.81659	0	0	0	
+0.75	-0.681639	-3.98998	5.81602	0	0	0	
+0.751	-0.68237	-3.99054	5.81546	0	0	0	
+0.752	-0.683101	-3.99108	5.81492	0	0	0	
+0.753	-0.683831	-3.99161	5.81439	0	0	0	
+0.754	-0.68456	-3.99212	5.81388	0	0	0	
+0.755	-0.685289	-3.99261	5.81339	0	0	0	
+0.756	-0.686017	-3.99309	5.81291	0	0	0	
+0.757	-0.686744	-3.99355	5.81245	0	0	0	
+0.758	-0.68747	-3.994	5.812	0	0	0	
+0.759	-0.688196	-3.99443	5.81157	0	0	0	
+0.76	-0.688921	-3.99484	5.81116	0	0	0	
+0.761	-0.689646	-3.99524	5.81076	0	0	0	
+0.762	-0.69037	-3.99562	5.81038	0	0	0	
+0.763	-0.691093	-3.99599	5.81001	0	0	0	
+0.764	-0.691815	-3.99634	5.80966	0	0	0	
+0.765	-0.692537	-3.99667	5.80933	0	0	0	
+0.766	-0.693258	-3.99699	5.80901	0	0	0	
+0.767	-0.693978	-3.99729	5.80871	0	0	0	
+0.768	-0.694698	-3.99758	5.80842	0	0	0	
+0.769	-0.695417	-3.99785	5.80815	0	0	0	
+0.77	-0.696135	-3.9981	5.8079	0	0	0	
+0.771	-0.696853	-3.99834	5.80766	0	0	0	
+0.772	-0.69757	-3.99856	5.80744	0	0	0	
+0.773	-0.698286	-3.99877	5.80723	0	0	0	
+0.774	-0.699001	-3.99896	5.80704	0	0	0	
+0.775	-0.699716	-3.99914	5.80686	0	0	0	
+0.776	-0.70043	-3.99929	5.80671	0	0	0	
+0.777	-0.701144	-3.99944	5.80656	0	0	0	
+0.778	-0.701856	-3.99956	5.80644	0	0	0	
+0.779	-0.702568	-3.99967	5.80633	0	0	0	
+0.78	-0.703279	-3.99977	5.80623	0	0	0	
+0.781	-0.70399	-3.99985	5.80615	0	0	0	
+0.782	-0.7047	-3.99991	5.80609	0	0	0	
+0.783	-0.705409	-3.99995	5.80605	0	0	0	
+0.784	-0.706117	-3.99998	5.80602	0	0	0	
+0.785	-0.706825	-4	5.806	0	0	0	
+0.786	-0.707532	-4	5.806	0	0	0	
+0.787	-0.708239	-3.99998	5.80602	0	0	0	
+0.788	-0.708944	-3.99995	5.80605	0	0	0	
+0.789	-0.709649	-3.9999	5.8061	0	0	0	
+0.79	-0.710353	-3.99983	5.80617	0	0	0	
+0.791	-0.711057	-3.99975	5.80625	0	0	0	
+0.792	-0.71176	-3.99965	5.80635	0	0	0	
+0.793	-0.712462	-3.99954	5.80646	0	0	0	
+0.794	-0.713163	-3.99941	5.80659	0	0	0	
+0.795	-0.713864	-3.99926	5.80674	0	0	0	
+0.796	-0.714564	-3.9991	5.8069	0	0	0	
+0.797	-0.715263	-3.99892	5.80708	0	0	0	
+0.798	-0.715961	-3.99873	5.80727	0	0	0	
+0.799	-0.716659	-3.99852	5.80748	0	0	0	
+0.8	-0.717356	-3.99829	5.80771	0	0	0	
+0.801	-0.718052	-3.99805	5.80795	0	0	0	
+0.802	-0.718748	-3.9978	5.8082	0	0	0	
+0.803	-0.719443	-3.99752	5.80848	0	0	0	
+0.804	-0.720137	-3.99723	5.80877	0	0	0	
+0.805	-0.720831	-3.99693	5.80907	0	0	0	
+0.806	-0.721523	-3.9966	5.8094	0	0	0	
+0.807	-0.722215	-3.99627	5.80973	0	0	0	
+0.808	-0.722907	-3.99591	5.81009	0	0	0	
+0.809	-0.723597	-3.99554	5.81046	0	0	0	
+0.81	-0.724287	-3.99516	5.81084	0	0	0	
+0.811	-0.724976	-3.99476	5.81124	0	0	0	
+0.812	-0.725665	-3.99434	5.81166	0	0	0	
+0.813	-0.726352	-3.99391	5.81209	0	0	0	
+0.814	-0.727039	-3.99346	5.81254	0	0	0	
+0.815	-0.727726	-3.99299	5.81301	0	0	0	
+0.816	-0.728411	-3.99251	5.81349	0	0	0	
+0.817	-0.729096	-3.99201	5.81399	0	0	0	
+0.818	-0.72978	-3.9915	5.8145	0	0	0	
+0.819	-0.730463	-3.99097	5.81503	0	0	0	
+0.82	-0.731146	-3.99043	5.81557	0	0	0	
+0.821	-0.731828	-3.98986	5.81614	0	0	0	
+0.822	-0.732509	-3.98929	5.81671	0	0	0	
+0.823	-0.733189	-3.98869	5.81731	0	0	0	
+0.824	-0.733869	-3.98809	5.81791	0	0	0	
+0.825	-0.734548	-3.98746	5.81854	0	0	0	
+0.826	-0.735226	-3.98682	5.81918	0	0	0	
+0.827	-0.735903	-3.98616	5.81984	0	0	0	
+0.828	-0.73658	-3.98549	5.82051	0	0	0	
+0.829	-0.737256	-3.9848	5.8212	0	0	0	
+0.83	-0.737931	-3.9841	5.8219	0	0	0	
+0.831	-0.738606	-3.98338	5.82262	0	0	0	
+0.832	-0.73928	-3.98264	5.82336	0	0	0	
+0.833	-0.739953	-3.98189	5.82411	0	0	0	
+0.834	-0.740625	-3.98112	5.82488	0	0	0	
+0.835	-0.741297	-3.98033	5.82567	0	0	0	
+0.836	-0.741967	-3.97953	5.82647	0	0	0	
+0.837	-0.742637	-3.97872	5.82728	0	0	0	
+0.838	-0.743307	-3.97788	5.82812	0	0	0	
+0.839	-0.743975	-3.97704	5.82896	0	0	0	
+0.84	-0.744643	-3.97617	5.82983	0	0	0	
+0.841	-0.74531	-3.97529	5.83071	0	0	0	
+0.842	-0.745977	-3.9744	5.8316	0	0	0	
+0.843	-0.746642	-3.97349	5.83251	0	0	0	
+0.844	-0.747307	-3.97256	5.83344	0	0	0	
+0.845	-0.747971	-3.97161	5.83439	0	0	0	
+0.846	-0.748634	-3.97066	5.83534	0	0	0	
+0.847	-0.749297	-3.96968	5.83632	0	0	0	
+0.848	-0.749959	-3.96869	5.83731	0	0	0	
+0.849	-0.75062	-3.96768	5.83832	0	0	0	
+0.85	-0.75128	-3.96666	5.83934	0	0	0	
+0.851	-0.75194	-3.96562	5.84038	0	0	0	
+0.852	-0.752599	-3.96457	5.84143	0	0	0	
+0.853	-0.753257	-3.9635	5.8425	0	0	0	
+0.854	-0.753914	-3.96241	5.84359	0	0	0	
+0.855	-0.754571	-3.96131	5.84469	0	0	0	
+0.856	-0.755227	-3.96019	5.84581	0	0	0	
+0.857	-0.755882	-3.95906	5.84694	0	0	0	
+0.858	-0.756536	-3.95791	5.84809	0	0	0	
+0.859	-0.75719	-3.95674	5.84926	0	0	0	
+0.86	-0.757843	-3.95556	5.85044	0	0	0	
+0.861	-0.758495	-3.95436	5.85164	0	0	0	
+0.862	-0.759146	-3.95315	5.85285	0	0	0	
+0.863	-0.759796	-3.95192	5.85408	0	0	0	
+0.864	-0.760446	-3.95068	5.85532	0	0	0	
+0.865	-0.761095	-3.94942	5.85658	0	0	0	
+0.866	-0.761744	-3.94814	5.85786	0	0	0	
+0.867	-0.762391	-3.94685	5.85915	0	0	0	
+0.868	-0.763038	-3.94554	5.86046	0	0	0	
+0.869	-0.763684	-3.94422	5.86178	0	0	0	
+0.87	-0.764329	-3.94288	5.86312	0	0	0	
+0.871	-0.764973	-3.94152	5.86448	0	0	0	
+0.872	-0.765617	-3.94015	5.86585	0	0	0	
+0.873	-0.76626	-3.93876	5.86724	0	0	0	
+0.874	-0.766902	-3.93736	5.86864	0	0	0	
+0.875	-0.767544	-3.93594	5.87006	0	0	0	
+0.876	-0.768184	-3.93451	5.87149	0	0	0	
+0.877	-0.768824	-3.93306	5.87294	0	0	0	
+0.878	-0.769463	-3.9316	5.8744	0	0	0	
+0.879	-0.770101	-3.93011	5.87589	0	0	0	
+0.88	-0.770739	-3.92862	5.87738	0	0	0	
+0.881	-0.771376	-3.9271	5.8789	0	0	0	
+0.882	-0.772012	-3.92558	5.88042	0	0	0	
+0.883	-0.772647	-3.92403	5.88197	0	0	0	
+0.884	-0.773281	-3.92247	5.88353	0	0	0	
+0.885	-0.773915	-3.9209	5.8851	0	0	0	
+0.886	-0.774548	-3.91931	5.88669	0	0	0	
+0.887	-0.77518	-3.9177	5.8883	0	0	0	
+0.888	-0.775811	-3.91608	5.88992	0	0	0	
+0.889	-0.776442	-3.91444	5.89156	0	0	0	
+0.89	-0.777072	-3.91279	5.89321	0	0	0	
+0.891	-0.777701	-3.91112	5.89488	0	0	0	
+0.892	-0.778329	-3.90943	5.89657	0	0	0	
+0.893	-0.778956	-3.90773	5.89827	0	0	0	
+0.894	-0.779583	-3.90602	5.89998	0	0	0	
+0.895	-0.780209	-3.90428	5.90172	0	0	0	
+0.896	-0.780834	-3.90254	5.90346	0	0	0	
+0.897	-0.781459	-3.90077	5.90523	0	0	0	
+0.898	-0.782082	-3.89899	5.90701	0	0	0	
+0.899	-0.782705	-3.8972	5.9088	0	0	0	
+0.9	-0.783327	-3.89539	5.91061	0	0	0	
+0.901	-0.783948	-3.89357	5.91243	0	0	0	
+0.902	-0.784569	-3.89172	5.91428	0	0	0	
+0.903	-0.785188	-3.88987	5.91613	0	0	0	
+0.904	-0.785807	-3.888	5.918	0	0	0	
+0.905	-0.786425	-3.88611	5.91989	0	0	0	
+0.906	-0.787042	-3.8842	5.9218	0	0	0	
+0.907	-0.787659	-3.88229	5.92371	0	0	0	
+0.908	-0.788275	-3.88035	5.92565	0	0	0	
+0.909	-0.78889	-3.8784	5.9276	0	0	0	
+0.91	-0.789504	-3.87644	5.92956	0	0	0	
+0.911	-0.790117	-3.87446	5.93154	0	0	0	
+0.912	-0.79073	-3.87246	5.93354	0	0	0	
+0.913	-0.791341	-3.87045	5.93555	0	0	0	
+0.914	-0.791952	-3.86842	5.93758	0	0	0	
+0.915	-0.792563	-3.86638	5.93962	0	0	0	
+0.916	-0.793172	-3.86432	5.94168	0	0	0	
+0.917	-0.793781	-3.86225	5.94375	0	0	0	
+0.918	-0.794388	-3.86016	5.94584	0	0	0	
+0.919	-0.794995	-3.85805	5.94795	0	0	0	
+0.92	-0.795602	-3.85593	5.95007	0	0	0	
+0.921	-0.796207	-3.8538	5.9522	0	0	0	
+0.922	-0.796812	-3.85165	5.95435	0	0	0	
+0.923	-0.797415	-3.84948	5.95652	0	0	0	
+0.924	-0.798019	-3.8473	5.9587	0	0	0	
+0.925	-0.798621	-3.8451	5.9609	0	0	0	
+0.926	-0.799222	-3.84289	5.96311	0	0	0	
+0.927	-0.799823	-3.84066	5.96534	0	0	0	
+0.928	-0.800423	-3.83842	5.96758	0	0	0	
+0.929	-0.801022	-3.83616	5.96984	0	0	0	
+0.93	-0.80162	-3.83389	5.97211	0	0	0	
+0.931	-0.802217	-3.8316	5.9744	0	0	0	
+0.932	-0.802814	-3.82929	5.97671	0	0	0	
+0.933	-0.80341	-3.82697	5.97903	0	0	0	
+0.934	-0.804005	-3.82464	5.98136	0	0	0	
+0.935	-0.804599	-3.82229	5.98371	0	0	0	
+0.936	-0.805192	-3.81992	5.98608	0	0	0	
+0.937	-0.805785	-3.81754	5.98846	0	0	0	
+0.938	-0.806377	-3.81514	5.99086	0	0	0	
+0.939	-0.806968	-3.81273	5.99327	0	0	0	
+0.94	-0.807558	-3.8103	5.9957	0	0	0	
+0.941	-0.808147	-3.80786	5.99814	0	0	0	
+0.942	-0.808736	-3.80541	6.00059	0	0	0	
+0.943	-0.809324	-3.80293	6.00307	0	0	0	
+0.944	-0.809911	-3.80045	6.00555	0	0	0	
+0.945	-0.810497	-3.79794	6.00806	0	0	0	
+0.946	-0.811082	-3.79542	6.01058	0	0	0	
+0.947	-0.811667	-3.79289	6.01311	0	0	0	
+0.948	-0.812251	-3.79034	6.01566	0	0	0	
+0.949	-0.812833	-3.78778	6.01822	0	0	0	
+0.95	-0.813416	-3.7852	6.0208	0	0	0	
+0.951	-0.813997	-3.78261	6.02339	0	0	0	
+0.952	-0.814577	-3.78	6.026	0	0	0	
+0.953	-0.815157	-3.77737	6.02863	0	0	0	
+0.954	-0.815736	-3.77473	6.03127	0	0	0	
+0.955	-0.816314	-3.77208	6.03392	0	0	0	
+0.956	-0.816891	-3.76941	6.03659	0	0	0	
+0.957	-0.817467	-3.76673	6.03927	0	0	0	
+0.958	-0.818043	-3.76403	6.04197	0	0	0	
+0.959	-0.818618	-3.76131	6.04469	0	0	0	
+0.96	-0.819192	-3.75858	6.04742	0	0	0	
+0.961	-0.819765	-3.75584	6.05016	0	0	0	
+0.962	-0.820337	-3.75308	6.05292	0	0	0	
+0.963	-0.820908	-3.7503	6.0557	0	0	0	
+0.964	-0.821479	-3.74751	6.05849	0	0	0	
+0.965	-0.822049	-3.74471	6.06129	0	0	0	
+0.966	-0.822618	-3.74189	6.06411	0	0	0	
+0.967	-0.823186	-3.73905	6.06695	0	0	0	
+0.968	-0.823753	-3.7362	6.0698	0	0	0	
+0.969	-0.82432	-3.73334	6.07266	0	0	0	
+0.97	-0.824886	-3.73046	6.07554	0	0	0	
+0.971	-0.825451	-3.72757	6.07843	0	0	0	
+0.972	-0.826015	-3.72466	6.08134	0	0	0	
+0.973	-0.826578	-3.72173	6.08427	0	0	0	
+0.974	-0.82714	-3.71879	6.08721	0	0	0	
+0.975	-0.827702	-3.71584	6.09016	0	0	0	
+0.976	-0.828263	-3.71287	6.09313	0	0	0	
+0.977	-0.828823	-3.70989	6.09611	0	0	0	
+0.978	-0.829382	-3.70689	6.09911	0	0	0	
+0.979	-0.82994	-3.70387	6.10213	0	0	0	
+0.98	-0.830497	-3.70085	6.10515	0	0	0	
+0.981	-0.831054	-3.6978	6.1082	0	0	0	
+0.982	-0.83161	-3.69475	6.11125	0	0	0	
+0.983	-0.832165	-3.69167	6.11433	0	0	0	
+0.984	-0.832719	-3.68859	6.11741	0	0	0	
+0.985	-0.833272	-3.68548	6.12052	0	0	0	
+0.986	-0.833825	-3.68237	6.12363	0	0	0	
+0.987	-0.834376	-3.67923	6.12677	0	0	0	
+0.988	-0.834927	-3.67609	6.12991	0	0	0	
+0.989	-0.835477	-3.67293	6.13307	0	0	0	
+0.99	-0.836026	-3.66975	6.13625	0	0	0	
+0.991	-0.836574	-3.66656	6.13944	0	0	0	
+0.992	-0.837122	-3.66336	6.14264	0	0	0	
+0.993	-0.837668	-3.66014	6.14586	0	0	0	
+0.994	-0.838214	-3.6569	6.1491	0	0	0	
+0.995	-0.838759	-3.65365	6.15235	0	0	0	
+0.996	-0.839303	-3.65039	6.15561	0	0	0	
+0.997	-0.839846	-3.64711	6.15889	0	0	0	
+0.998	-0.840389	-3.64382	6.16218	0	0	0	
+0.999	-0.84093	-3.64051	6.16549	0	0	0	
+1	-0.841471	-3.63719	6.16881	0	0	0	
+1.001	-0.842011	-3.63385	6.17215	0	0	0	
+1.002	-0.84255	-3.6305	6.1755	0	0	0	
+1.003	-0.843088	-3.62714	6.17886	0	0	0	
+1.004	-0.843625	-3.62376	6.18224	0	0	0	
+1.005	-0.844162	-3.62036	6.18564	0	0	0	
+1.006	-0.844698	-3.61695	6.18905	0	0	0	
+1.007	-0.845232	-3.61353	6.19247	0	0	0	
+1.008	-0.845766	-3.61009	6.19591	0	0	0	
+1.009	-0.8463	-3.60664	6.19936	0	0	0	
+1.01	-0.846832	-3.60317	6.20283	0	0	0	
+1.011	-0.847363	-3.59969	6.20631	0	0	0	
+1.012	-0.847894	-3.5962	6.2098	0	0	0	
+1.013	-0.848424	-3.59269	6.21331	0	0	0	
+1.014	-0.848953	-3.58916	6.21684	0	0	0	
+1.015	-0.849481	-3.58562	6.22038	0	0	0	
+1.016	-0.850008	-3.58207	6.22393	0	0	0	
+1.017	-0.850534	-3.5785	6.2275	0	0	0	
+1.018	-0.85106	-3.57492	6.23108	0	0	0	
+1.019	-0.851584	-3.57132	6.23468	0	0	0	
+1.02	-0.852108	-3.56771	6.23829	0	0	0	
+1.021	-0.852631	-3.56409	6.24191	0	0	0	
+1.022	-0.853153	-3.56045	6.24555	0	0	0	
+1.023	-0.853674	-3.5568	6.2492	0	0	0	
+1.024	-0.854195	-3.55313	6.25287	0	0	0	
+1.025	-0.854714	-3.54945	6.25655	0	0	0	
+1.026	-0.855233	-3.54575	6.26025	0	0	0	
+1.027	-0.855751	-3.54204	6.26396	0	0	0	
+1.028	-0.856268	-3.53832	6.26768	0	0	0	
+1.029	-0.856784	-3.53458	6.27142	0	0	0	
+1.03	-0.857299	-3.53083	6.27517	0	0	0	
+1.031	-0.857813	-3.52706	6.27894	0	0	0	
+1.032	-0.858327	-3.52328	6.28272	0	0	0	
+1.033	-0.85884	-3.51949	6.28651	0	0	0	
+1.034	-0.859351	-3.51568	6.29032	0	0	0	
+1.035	-0.859862	-3.51186	6.29414	0	0	0	
+1.036	-0.860372	-3.50802	6.29798	0	0	0	
+1.037	-0.860882	-3.50417	6.30183	0	0	0	
+1.038	-0.86139	-3.5003	6.3057	0	0	0	
+1.039	-0.861898	-3.49642	6.30958	0	0	0	
+1.04	-0.862404	-3.49253	6.31347	0	0	0	
+1.041	-0.86291	-3.48863	6.31737	0	0	0	
+1.042	-0.863415	-3.4847	6.3213	0	0	0	
+1.043	-0.863919	-3.48077	6.32523	0	0	0	
+1.044	-0.864422	-3.47682	6.32918	0	0	0	
+1.045	-0.864925	-3.47286	6.33314	0	0	0	
+1.046	-0.865426	-3.46888	6.33712	0	0	0	
+1.047	-0.865927	-3.46489	6.34111	0	0	0	
+1.048	-0.866426	-3.46089	6.34511	0	0	0	
+1.049	-0.866925	-3.45687	6.34913	0	0	0	
+1.05	-0.867423	-3.45284	6.35316	0	0	0	
+1.051	-0.86792	-3.44879	6.35721	0	0	0	
+1.052	-0.868417	-3.44473	6.36127	0	0	0	
+1.053	-0.868912	-3.44066	6.36534	0	0	0	
+1.054	-0.869407	-3.43657	6.36943	0	0	0	
+1.055	-0.8699	-3.43247	6.37353	0	0	0	
+1.056	-0.870393	-3.42836	6.37764	0	0	0	
+1.057	-0.870885	-3.42423	6.38177	0	0	0	
+1.058	-0.871376	-3.42009	6.38591	0	0	0	
+1.059	-0.871866	-3.41593	6.39007	0	0	0	
+1.06	-0.872355	-3.41176	6.39424	0	0	0	
+1.061	-0.872844	-3.40758	6.39842	0	0	0	
+1.062	-0.873331	-3.40338	6.40262	0	0	0	
+1.063	-0.873818	-3.39917	6.40683	0	0	0	
+1.064	-0.874304	-3.39495	6.41105	0	0	0	
+1.065	-0.874789	-3.39071	6.41529	0	0	0	
+1.066	-0.875273	-3.38646	6.41954	0	0	0	
+1.067	-0.875756	-3.3822	6.4238	0	0	0	
+1.068	-0.876239	-3.37792	6.42808	0	0	0	
+1.069	-0.87672	-3.37363	6.43237	0	0	0	
+1.07	-0.877201	-3.36932	6.43668	0	0	0	
+1.071	-0.87768	-3.365	6.441	0	0	0	
+1.072	-0.878159	-3.36067	6.44533	0	0	0	
+1.073	-0.878637	-3.35633	6.44967	0	0	0	
+1.074	-0.879114	-3.35197	6.45403	0	0	0	
+1.075	-0.87959	-3.3476	6.4584	0	0	0	
+1.076	-0.880065	-3.34321	6.46279	0	0	0	
+1.077	-0.88054	-3.33881	6.46719	0	0	0	
+1.078	-0.881013	-3.3344	6.4716	0	0	0	
+1.079	-0.881486	-3.32997	6.47603	0	0	0	
+1.08	-0.881958	-3.32553	6.48047	0	0	0	
+1.081	-0.882429	-3.32108	6.48492	0	0	0	
+1.082	-0.882899	-3.31662	6.48938	0	0	0	
+1.083	-0.883368	-3.31214	6.49386	0	0	0	
+1.084	-0.883836	-3.30765	6.49835	0	0	0	
+1.085	-0.884303	-3.30314	6.50286	0	0	0	
+1.086	-0.88477	-3.29862	6.50738	0	0	0	
+1.087	-0.885235	-3.29409	6.51191	0	0	0	
+1.088	-0.8857	-3.28954	6.51646	0	0	0	
+1.089	-0.886164	-3.28499	6.52101	0	0	0	
+1.09	-0.886627	-3.28042	6.52558	0	0	0	
+1.091	-0.887089	-3.27583	6.53017	0	0	0	
+1.092	-0.88755	-3.27123	6.53477	0	0	0	
+1.093	-0.88801	-3.26662	6.53938	0	0	0	
+1.094	-0.88847	-3.262	6.544	0	0	0	
+1.095	-0.888928	-3.25736	6.54864	0	0	0	
+1.096	-0.889386	-3.25271	6.55329	0	0	0	
+1.097	-0.889843	-3.24805	6.55795	0	0	0	
+1.098	-0.890298	-3.24338	6.56262	0	0	0	
+1.099	-0.890753	-3.23869	6.56731	0	0	0	
+1.1	-0.891207	-3.23399	6.57201	0	0	0	
+1.101	-0.891661	-3.22927	6.57673	0	0	0	
+1.102	-0.892113	-3.22454	6.58146	0	0	0	
+1.103	-0.892564	-3.2198	6.5862	0	0	0	
+1.104	-0.893015	-3.21505	6.59095	0	0	0	
+1.105	-0.893464	-3.21028	6.59572	0	0	0	
+1.106	-0.893913	-3.20551	6.60049	0	0	0	
+1.107	-0.894361	-3.20071	6.60529	0	0	0	
+1.108	-0.894808	-3.19591	6.61009	0	0	0	
+1.109	-0.895254	-3.19109	6.61491	0	0	0	
+1.11	-0.895699	-3.18626	6.61974	0	0	0	
+1.111	-0.896143	-3.18142	6.62458	0	0	0	
+1.112	-0.896586	-3.17656	6.62944	0	0	0	
+1.113	-0.897029	-3.1717	6.6343	0	0	0	
+1.114	-0.89747	-3.16681	6.63919	0	0	0	
+1.115	-0.897911	-3.16192	6.64408	0	0	0	
+1.116	-0.898351	-3.15701	6.64899	0	0	0	
+1.117	-0.898789	-3.1521	6.6539	0	0	0	
+1.118	-0.899227	-3.14716	6.65884	0	0	0	
+1.119	-0.899664	-3.14222	6.66378	0	0	0	
+1.12	-0.9001	-3.13726	6.66874	0	0	0	
+1.121	-0.900536	-3.13229	6.67371	0	0	0	
+1.122	-0.90097	-3.12731	6.67869	0	0	0	
+1.123	-0.901403	-3.12232	6.68368	0	0	0	
+1.124	-0.901836	-3.11731	6.68869	0	0	0	
+1.125	-0.902268	-3.11229	6.69371	0	0	0	
+1.126	-0.902698	-3.10726	6.69874	0	0	0	
+1.127	-0.903128	-3.10222	6.70378	0	0	0	
+1.128	-0.903557	-3.09716	6.70884	0	0	0	
+1.129	-0.903985	-3.09209	6.71391	0	0	0	
+1.13	-0.904412	-3.08701	6.71899	0	0	0	
+1.131	-0.904838	-3.08192	6.72408	0	0	0	
+1.132	-0.905264	-3.07681	6.72919	0	0	0	
+1.133	-0.905688	-3.07169	6.73431	0	0	0	
+1.134	-0.906112	-3.06656	6.73944	0	0	0	
+1.135	-0.906534	-3.06142	6.74458	0	0	0	
+1.136	-0.906956	-3.05626	6.74974	0	0	0	
+1.137	-0.907377	-3.0511	6.7549	0	0	0	
+1.138	-0.907796	-3.04592	6.76008	0	0	0	
+1.139	-0.908215	-3.04073	6.76527	0	0	0	
+1.14	-0.908633	-3.03552	6.77048	0	0	0	
+1.141	-0.909051	-3.03031	6.77569	0	0	0	
+1.142	-0.909467	-3.02508	6.78092	0	0	0	
+1.143	-0.909882	-3.01984	6.78616	0	0	0	
+1.144	-0.910297	-3.01459	6.79141	0	0	0	
+1.145	-0.91071	-3.00932	6.79668	0	0	0	
+1.146	-0.911123	-3.00405	6.80195	0	0	0	
+1.147	-0.911534	-2.99876	6.80724	0	0	0	
+1.148	-0.911945	-2.99346	6.81254	0	0	0	
+1.149	-0.912355	-2.98815	6.81785	0	0	0	
+1.15	-0.912764	-2.98282	6.82318	0	0	0	
+1.151	-0.913172	-2.97748	6.82852	0	0	0	
+1.152	-0.913579	-2.97214	6.83386	0	0	0	
+1.153	-0.913985	-2.96678	6.83922	0	0	0	
+1.154	-0.914391	-2.9614	6.8446	0	0	0	
+1.155	-0.914795	-2.95602	6.84998	0	0	0	
+1.156	-0.915198	-2.95063	6.85537	0	0	0	
+1.157	-0.915601	-2.94522	6.86078	0	0	0	
+1.158	-0.916003	-2.9398	6.8662	0	0	0	
+1.159	-0.916403	-2.93437	6.87163	0	0	0	
+1.16	-0.916803	-2.92893	6.87707	0	0	0	
+1.161	-0.917202	-2.92347	6.88253	0	0	0	
+1.162	-0.9176	-2.91801	6.88799	0	0	0	
+1.163	-0.917997	-2.91253	6.89347	0	0	0	
+1.164	-0.918393	-2.90704	6.89896	0	0	0	
+1.165	-0.918788	-2.90154	6.90446	0	0	0	
+1.166	-0.919183	-2.89602	6.90998	0	0	0	
+1.167	-0.919576	-2.8905	6.9155	0	0	0	
+1.168	-0.919968	-2.88497	6.92103	0	0	0	
+1.169	-0.92036	-2.87942	6.92658	0	0	0	
+1.17	-0.920751	-2.87386	6.93214	0	0	0	
+1.171	-0.92114	-2.86829	6.93771	0	0	0	
+1.172	-0.921529	-2.86271	6.94329	0	0	0	
+1.173	-0.921917	-2.85711	6.94889	0	0	0	
+1.174	-0.922304	-2.85151	6.95449	0	0	0	
+1.175	-0.92269	-2.84589	6.96011	0	0	0	
+1.176	-0.923075	-2.84027	6.96573	0	0	0	
+1.177	-0.923459	-2.83463	6.97137	0	0	0	
+1.178	-0.923842	-2.82898	6.97702	0	0	0	
+1.179	-0.924225	-2.82332	6.98268	0	0	0	
+1.18	-0.924606	-2.81764	6.98836	0	0	0	
+1.181	-0.924986	-2.81196	6.99404	0	0	0	
+1.182	-0.925366	-2.80626	6.99974	0	0	0	
+1.183	-0.925745	-2.80056	7.00544	0	0	0	
+1.184	-0.926122	-2.79484	7.01116	0	0	0	
+1.185	-0.926499	-2.78911	7.01689	0	0	0	
+1.186	-0.926875	-2.78337	7.02263	0	0	0	
+1.187	-0.92725	-2.77762	7.02838	0	0	0	
+1.188	-0.927624	-2.77186	7.03414	0	0	0	
+1.189	-0.927997	-2.76608	7.03992	0	0	0	
+1.19	-0.928369	-2.7603	7.0457	0	0	0	
+1.191	-0.92874	-2.7545	7.0515	0	0	0	
+1.192	-0.92911	-2.7487	7.0573	0	0	0	
+1.193	-0.92948	-2.74288	7.06312	0	0	0	
+1.194	-0.929848	-2.73705	7.06895	0	0	0	
+1.195	-0.930216	-2.73121	7.07479	0	0	0	
+1.196	-0.930582	-2.72536	7.08064	0	0	0	
+1.197	-0.930948	-2.7195	7.0865	0	0	0	
+1.198	-0.931313	-2.71363	7.09237	0	0	0	
+1.199	-0.931676	-2.70775	7.09825	0	0	0	
+1.2	-0.932039	-2.70185	7.10415	0	0	0	
+1.201	-0.932401	-2.69595	7.11005	0	0	0	
+1.202	-0.932762	-2.69003	7.11597	0	0	0	
+1.203	-0.933122	-2.68411	7.12189	0	0	0	
+1.204	-0.933481	-2.67817	7.12783	0	0	0	
+1.205	-0.933839	-2.67222	7.13378	0	0	0	
+1.206	-0.934196	-2.66626	7.13974	0	0	0	
+1.207	-0.934553	-2.6603	7.1457	0	0	0	
+1.208	-0.934908	-2.65432	7.15168	0	0	0	
+1.209	-0.935263	-2.64833	7.15767	0	0	0	
+1.21	-0.935616	-2.64232	7.16368	0	0	0	
+1.211	-0.935969	-2.63631	7.16969	0	0	0	
+1.212	-0.93632	-2.63029	7.17571	0	0	0	
+1.213	-0.936671	-2.62426	7.18174	0	0	0	
+1.214	-0.937021	-2.61822	7.18778	0	0	0	
+1.215	-0.937369	-2.61216	7.19384	0	0	0	
+1.216	-0.937717	-2.6061	7.1999	0	0	0	
+1.217	-0.938064	-2.60002	7.20598	0	0	0	
+1.218	-0.93841	-2.59394	7.21206	0	0	0	
+1.219	-0.938755	-2.58785	7.21815	0	0	0	
+1.22	-0.939099	-2.58174	7.22426	0	0	0	
+1.221	-0.939443	-2.57562	7.23038	0	0	0	
+1.222	-0.939785	-2.5695	7.2365	0	0	0	
+1.223	-0.940126	-2.56336	7.24264	0	0	0	
+1.224	-0.940466	-2.55722	7.24878	0	0	0	
+1.225	-0.940806	-2.55106	7.25494	0	0	0	
+1.226	-0.941144	-2.54489	7.26111	0	0	0	
+1.227	-0.941482	-2.53871	7.26729	0	0	0	
+1.228	-0.941818	-2.53253	7.27347	0	0	0	
+1.229	-0.942154	-2.52633	7.27967	0	0	0	
+1.23	-0.942489	-2.52012	7.28588	0	0	0	
+1.231	-0.942823	-2.5139	7.2921	0	0	0	
+1.232	-0.943155	-2.50768	7.29832	0	0	0	
+1.233	-0.943487	-2.50144	7.30456	0	0	0	
+1.234	-0.943818	-2.49519	7.31081	0	0	0	
+1.235	-0.944148	-2.48893	7.31707	0	0	0	
+1.236	-0.944477	-2.48267	7.32333	0	0	0	
+1.237	-0.944805	-2.47639	7.32961	0	0	0	
+1.238	-0.945133	-2.4701	7.3359	0	0	0	
+1.239	-0.945459	-2.4638	7.3422	0	0	0	
+1.24	-0.945784	-2.4575	7.3485	0	0	0	
+1.241	-0.946108	-2.45118	7.35482	0	0	0	
+1.242	-0.946432	-2.44485	7.36115	0	0	0	
+1.243	-0.946754	-2.43852	7.36748	0	0	0	
+1.244	-0.947076	-2.43217	7.37383	0	0	0	
+1.245	-0.947396	-2.42581	7.38019	0	0	0	
+1.246	-0.947716	-2.41945	7.38655	0	0	0	
+1.247	-0.948034	-2.41307	7.39293	0	0	0	
+1.248	-0.948352	-2.40669	7.39931	0	0	0	
+1.249	-0.948669	-2.40029	7.40571	0	0	0	
+1.25	-0.948985	-2.39389	7.41211	0	0	0	
+1.251	-0.949299	-2.38747	7.41853	0	0	0	
+1.252	-0.949613	-2.38105	7.42495	0	0	0	
+1.253	-0.949926	-2.37462	7.43138	0	0	0	
+1.254	-0.950238	-2.36818	7.43782	0	0	0	
+1.255	-0.950549	-2.36172	7.44428	0	0	0	
+1.256	-0.950859	-2.35526	7.45074	0	0	0	
+1.257	-0.951169	-2.34879	7.45721	0	0	0	
+1.258	-0.951477	-2.34231	7.46369	0	0	0	
+1.259	-0.951784	-2.33582	7.47018	0	0	0	
+1.26	-0.95209	-2.32932	7.47668	0	0	0	
+1.261	-0.952396	-2.32281	7.48319	0	0	0	
+1.262	-0.9527	-2.3163	7.4897	0	0	0	
+1.263	-0.953004	-2.30977	7.49623	0	0	0	
+1.264	-0.953306	-2.30323	7.50277	0	0	0	
+1.265	-0.953608	-2.29669	7.50931	0	0	0	
+1.266	-0.953908	-2.29013	7.51587	0	0	0	
+1.267	-0.954208	-2.28357	7.52243	0	0	0	
+1.268	-0.954506	-2.277	7.529	0	0	0	
+1.269	-0.954804	-2.27042	7.53558	0	0	0	
+1.27	-0.955101	-2.26382	7.54218	0	0	0	
+1.271	-0.955397	-2.25722	7.54878	0	0	0	
+1.272	-0.955692	-2.25062	7.55538	0	0	0	
+1.273	-0.955985	-2.244	7.562	0	0	0	
+1.274	-0.956278	-2.23737	7.56863	0	0	0	
+1.275	-0.95657	-2.23073	7.57527	0	0	0	
+1.276	-0.956861	-2.22409	7.58191	0	0	0	
+1.277	-0.957151	-2.21744	7.58856	0	0	0	
+1.278	-0.957441	-2.21077	7.59523	0	0	0	
+1.279	-0.957729	-2.2041	7.6019	0	0	0	
+1.28	-0.958016	-2.19742	7.60858	0	0	0	
+1.281	-0.958302	-2.19073	7.61527	0	0	0	
+1.282	-0.958587	-2.18403	7.62197	0	0	0	
+1.283	-0.958872	-2.17733	7.62867	0	0	0	
+1.284	-0.959155	-2.17061	7.63539	0	0	0	
+1.285	-0.959437	-2.16389	7.64211	0	0	0	
+1.286	-0.959719	-2.15716	7.64884	0	0	0	
+1.287	-0.959999	-2.15041	7.65559	0	0	0	
+1.288	-0.960279	-2.14367	7.66233	0	0	0	
+1.289	-0.960557	-2.13691	7.66909	0	0	0	
+1.29	-0.960835	-2.13014	7.67586	0	0	0	
+1.291	-0.961112	-2.12336	7.68264	0	0	0	
+1.292	-0.961387	-2.11658	7.68942	0	0	0	
+1.293	-0.961662	-2.10979	7.69621	0	0	0	
+1.294	-0.961936	-2.10299	7.70301	0	0	0	
+1.295	-0.962209	-2.09618	7.70982	0	0	0	
+1.296	-0.96248	-2.08936	7.71664	0	0	0	
+1.297	-0.962751	-2.08253	7.72347	0	0	0	
+1.298	-0.963021	-2.0757	7.7303	0	0	0	
+1.299	-0.96329	-2.06886	7.73714	0	0	0	
+1.3	-0.963558	-2.06201	7.74399	0	0	0	
+1.301	-0.963825	-2.05515	7.75085	0	0	0	
+1.302	-0.964091	-2.04828	7.75772	0	0	0	
+1.303	-0.964356	-2.0414	7.7646	0	0	0	
+1.304	-0.96462	-2.03452	7.77148	0	0	0	
+1.305	-0.964884	-2.02763	7.77837	0	0	0	
+1.306	-0.965146	-2.02073	7.78527	0	0	0	
+1.307	-0.965407	-2.01382	7.79218	0	0	0	
+1.308	-0.965667	-2.0069	7.7991	0	0	0	
+1.309	-0.965927	-1.99998	7.80602	0	0	0	
+1.31	-0.966185	-1.99305	7.81295	0	0	0	
+1.311	-0.966442	-1.98611	7.81989	0	0	0	
+1.312	-0.966699	-1.97916	7.82684	0	0	0	
+1.313	-0.966954	-1.9722	7.8338	0	0	0	
+1.314	-0.967209	-1.96524	7.84076	0	0	0	
+1.315	-0.967462	-1.95827	7.84773	0	0	0	
+1.316	-0.967715	-1.95129	7.85471	0	0	0	
+1.317	-0.967966	-1.9443	7.8617	0	0	0	
+1.318	-0.968217	-1.9373	7.8687	0	0	0	
+1.319	-0.968466	-1.9303	7.8757	0	0	0	
+1.32	-0.968715	-1.92329	7.88271	0	0	0	
+1.321	-0.968963	-1.91627	7.88973	0	0	0	
+1.322	-0.96921	-1.90925	7.89675	0	0	0	
+1.323	-0.969455	-1.90221	7.90379	0	0	0	
+1.324	-0.9697	-1.89517	7.91083	0	0	0	
+1.325	-0.969944	-1.88812	7.91788	0	0	0	
+1.326	-0.970187	-1.88107	7.92493	0	0	0	
+1.327	-0.970429	-1.874	7.932	0	0	0	
+1.328	-0.970669	-1.86693	7.93907	0	0	0	
+1.329	-0.970909	-1.85985	7.94615	0	0	0	
+1.33	-0.971148	-1.85277	7.95323	0	0	0	
+1.331	-0.971386	-1.84567	7.96033	0	0	0	
+1.332	-0.971623	-1.83857	7.96743	0	0	0	
+1.333	-0.971859	-1.83146	7.97454	0	0	0	
+1.334	-0.972095	-1.82435	7.98165	0	0	0	
+1.335	-0.972329	-1.81722	7.98878	0	0	0	
+1.336	-0.972562	-1.81009	7.99591	0	0	0	
+1.337	-0.972794	-1.80295	8.00305	0	0	0	
+1.338	-0.973025	-1.79581	8.01019	0	0	0	
+1.339	-0.973255	-1.78866	8.01734	0	0	0	
+1.34	-0.973485	-1.7815	8.0245	0	0	0	
+1.341	-0.973713	-1.77433	8.03167	0	0	0	
+1.342	-0.97394	-1.76716	8.03884	0	0	0	
+1.343	-0.974166	-1.75998	8.04602	0	0	0	
+1.344	-0.974392	-1.75279	8.05321	0	0	0	
+1.345	-0.974616	-1.7456	8.0604	0	0	0	
+1.346	-0.97484	-1.73839	8.06761	0	0	0	
+1.347	-0.975062	-1.73119	8.07481	0	0	0	
+1.348	-0.975283	-1.72397	8.08203	0	0	0	
+1.349	-0.975504	-1.71675	8.08925	0	0	0	
+1.35	-0.975723	-1.70952	8.09648	0	0	0	
+1.351	-0.975942	-1.70228	8.10372	0	0	0	
+1.352	-0.976159	-1.69504	8.11096	0	0	0	
+1.353	-0.976376	-1.68779	8.11821	0	0	0	
+1.354	-0.976592	-1.68053	8.12547	0	0	0	
+1.355	-0.976806	-1.67327	8.13273	0	0	0	
+1.356	-0.97702	-1.666	8.14	0	0	0	
+1.357	-0.977232	-1.65873	8.14727	0	0	0	
+1.358	-0.977444	-1.65144	8.15456	0	0	0	
+1.359	-0.977655	-1.64415	8.16185	0	0	0	
+1.36	-0.977865	-1.63686	8.16914	0	0	0	
+1.361	-0.978073	-1.62955	8.17645	0	0	0	
+1.362	-0.978281	-1.62224	8.18376	0	0	0	
+1.363	-0.978488	-1.61493	8.19107	0	0	0	
+1.364	-0.978694	-1.60761	8.19839	0	0	0	
+1.365	-0.978899	-1.60028	8.20572	0	0	0	
+1.366	-0.979102	-1.59294	8.21306	0	0	0	
+1.367	-0.979305	-1.5856	8.2204	0	0	0	
+1.368	-0.979507	-1.57825	8.22775	0	0	0	
+1.369	-0.979708	-1.5709	8.2351	0	0	0	
+1.37	-0.979908	-1.56354	8.24246	0	0	0	
+1.371	-0.980107	-1.55617	8.24983	0	0	0	
+1.372	-0.980305	-1.5488	8.2572	0	0	0	
+1.373	-0.980502	-1.54142	8.26458	0	0	0	
+1.374	-0.980698	-1.53404	8.27196	0	0	0	
+1.375	-0.980893	-1.52664	8.27936	0	0	0	
+1.376	-0.981087	-1.51925	8.28675	0	0	0	
+1.377	-0.98128	-1.51184	8.29416	0	0	0	
+1.378	-0.981472	-1.50443	8.30157	0	0	0	
+1.379	-0.981663	-1.49702	8.30898	0	0	0	
+1.38	-0.981854	-1.4896	8.3164	0	0	0	
+1.381	-0.982043	-1.48217	8.32383	0	0	0	
+1.382	-0.982231	-1.47474	8.33126	0	0	0	
+1.383	-0.982418	-1.4673	8.3387	0	0	0	
+1.384	-0.982604	-1.45985	8.34615	0	0	0	
+1.385	-0.982789	-1.4524	8.3536	0	0	0	
+1.386	-0.982974	-1.44494	8.36106	0	0	0	
+1.387	-0.983157	-1.43748	8.36852	0	0	0	
+1.388	-0.983339	-1.43001	8.37599	0	0	0	
+1.389	-0.983521	-1.42254	8.38346	0	0	0	
+1.39	-0.983701	-1.41506	8.39094	0	0	0	
+1.391	-0.98388	-1.40757	8.39843	0	0	0	
+1.392	-0.984058	-1.40008	8.40592	0	0	0	
+1.393	-0.984236	-1.39258	8.41342	0	0	0	
+1.394	-0.984412	-1.38508	8.42092	0	0	0	
+1.395	-0.984588	-1.37757	8.42843	0	0	0	
+1.396	-0.984762	-1.37006	8.43594	0	0	0	
+1.397	-0.984935	-1.36254	8.44346	0	0	0	
+1.398	-0.985108	-1.35502	8.45098	0	0	0	
+1.399	-0.985279	-1.34749	8.45851	0	0	0	
+1.4	-0.98545	-1.33995	8.46605	0	0	0	
+1.401	-0.985619	-1.33241	8.47359	0	0	0	
+1.402	-0.985788	-1.32487	8.48113	0	0	0	
+1.403	-0.985955	-1.31732	8.48868	0	0	0	
+1.404	-0.986122	-1.30976	8.49624	0	0	0	
+1.405	-0.986287	-1.3022	8.5038	0	0	0	
+1.406	-0.986452	-1.29463	8.51137	0	0	0	
+1.407	-0.986615	-1.28706	8.51894	0	0	0	
+1.408	-0.986778	-1.27948	8.52652	0	0	0	
+1.409	-0.98694	-1.2719	8.5341	0	0	0	
+1.41	-0.9871	-1.26431	8.54169	0	0	0	
+1.411	-0.98726	-1.25672	8.54928	0	0	0	
+1.412	-0.987418	-1.24912	8.55688	0	0	0	
+1.413	-0.987576	-1.24152	8.56448	0	0	0	
+1.414	-0.987733	-1.23391	8.57209	0	0	0	
+1.415	-0.987888	-1.2263	8.5797	0	0	0	
+1.416	-0.988043	-1.21868	8.58732	0	0	0	
+1.417	-0.988197	-1.21106	8.59494	0	0	0	
+1.418	-0.988349	-1.20343	8.60257	0	0	0	
+1.419	-0.988501	-1.1958	8.6102	0	0	0	
+1.42	-0.988652	-1.18817	8.61783	0	0	0	
+1.421	-0.988801	-1.18052	8.62548	0	0	0	
+1.422	-0.98895	-1.17288	8.63312	0	0	0	
+1.423	-0.989098	-1.16523	8.64077	0	0	0	
+1.424	-0.989245	-1.15757	8.64843	0	0	0	
+1.425	-0.989391	-1.14991	8.65609	0	0	0	
+1.426	-0.989535	-1.14225	8.66375	0	0	0	
+1.427	-0.989679	-1.13458	8.67142	0	0	0	
+1.428	-0.989822	-1.1269	8.6791	0	0	0	
+1.429	-0.989964	-1.11923	8.68677	0	0	0	
+1.43	-0.990105	-1.11154	8.69446	0	0	0	
+1.431	-0.990244	-1.10386	8.70214	0	0	0	
+1.432	-0.990383	-1.09617	8.70983	0	0	0	
+1.433	-0.990521	-1.08847	8.71753	0	0	0	
+1.434	-0.990658	-1.08077	8.72523	0	0	0	
+1.435	-0.990794	-1.07306	8.73294	0	0	0	
+1.436	-0.990929	-1.06536	8.74064	0	0	0	
+1.437	-0.991063	-1.05764	8.74836	0	0	0	
+1.438	-0.991196	-1.04992	8.75608	0	0	0	
+1.439	-0.991327	-1.0422	8.7638	0	0	0	
+1.44	-0.991458	-1.03448	8.77152	0	0	0	
+1.441	-0.991588	-1.02675	8.77925	0	0	0	
+1.442	-0.991717	-1.01901	8.78699	0	0	0	
+1.443	-0.991845	-1.01128	8.79472	0	0	0	
+1.444	-0.991972	-1.00353	8.80247	0	0	0	
+1.445	-0.992098	-0.995787	8.81021	0	0	0	
+1.446	-0.992223	-0.988037	8.81796	0	0	0	
+1.447	-0.992347	-0.980283	8.82572	0	0	0	
+1.448	-0.99247	-0.972525	8.83348	0	0	0	
+1.449	-0.992592	-0.964763	8.84124	0	0	0	
+1.45	-0.992713	-0.956997	8.849	0	0	0	
+1.451	-0.992833	-0.949228	8.85677	0	0	0	
+1.452	-0.992952	-0.941454	8.86455	0	0	0	
+1.453	-0.99307	-0.933677	8.87232	0	0	0	
+1.454	-0.993187	-0.925896	8.8801	0	0	0	
+1.455	-0.993303	-0.918112	8.88789	0	0	0	
+1.456	-0.993418	-0.910324	8.89568	0	0	0	
+1.457	-0.993532	-0.902532	8.90347	0	0	0	
+1.458	-0.993645	-0.894736	8.91126	0	0	0	
+1.459	-0.993757	-0.886937	8.91906	0	0	0	
+1.46	-0.993868	-0.879134	8.92687	0	0	0	
+1.461	-0.993978	-0.871328	8.93467	0	0	0	
+1.462	-0.994088	-0.863519	8.94248	0	0	0	
+1.463	-0.994196	-0.855706	8.95029	0	0	0	
+1.464	-0.994303	-0.847889	8.95811	0	0	0	
+1.465	-0.994409	-0.840069	8.96593	0	0	0	
+1.466	-0.994514	-0.832246	8.97375	0	0	0	
+1.467	-0.994618	-0.824419	8.98158	0	0	0	
+1.468	-0.994721	-0.816589	8.98941	0	0	0	
+1.469	-0.994823	-0.808756	8.99724	0	0	0	
+1.47	-0.994924	-0.80092	9.00508	0	0	0	
+1.471	-0.995024	-0.79308	9.01292	0	0	0	
+1.472	-0.995124	-0.785238	9.02076	0	0	0	
+1.473	-0.995222	-0.777392	9.02861	0	0	0	
+1.474	-0.995319	-0.769543	9.03646	0	0	0	
+1.475	-0.995415	-0.761691	9.04431	0	0	0	
+1.476	-0.99551	-0.753835	9.05216	0	0	0	
+1.477	-0.995604	-0.745977	9.06002	0	0	0	
+1.478	-0.995698	-0.738116	9.06788	0	0	0	
+1.479	-0.99579	-0.730252	9.07575	0	0	0	
+1.48	-0.995881	-0.722385	9.08361	0	0	0	
+1.481	-0.995971	-0.714515	9.09148	0	0	0	
+1.482	-0.99606	-0.706642	9.09936	0	0	0	
+1.483	-0.996148	-0.698767	9.10723	0	0	0	
+1.484	-0.996236	-0.690888	9.11511	0	0	0	
+1.485	-0.996322	-0.683007	9.12299	0	0	0	
+1.486	-0.996407	-0.675123	9.13088	0	0	0	
+1.487	-0.996491	-0.667237	9.13876	0	0	0	
+1.488	-0.996574	-0.659348	9.14665	0	0	0	
+1.489	-0.996657	-0.651456	9.15454	0	0	0	
+1.49	-0.996738	-0.643561	9.16244	0	0	0	
+1.491	-0.996818	-0.635664	9.17034	0	0	0	
+1.492	-0.996897	-0.627765	9.17824	0	0	0	
+1.493	-0.996975	-0.619862	9.18614	0	0	0	
+1.494	-0.997053	-0.611958	9.19404	0	0	0	
+1.495	-0.997129	-0.604051	9.20195	0	0	0	
+1.496	-0.997204	-0.596141	9.20986	0	0	0	
+1.497	-0.997278	-0.58823	9.21777	0	0	0	
+1.498	-0.997352	-0.580315	9.22568	0	0	0	
+1.499	-0.997424	-0.572399	9.2336	0	0	0	
+1.5	-0.997495	-0.56448	9.24152	0	0	0	
+1.501	-0.997565	-0.556559	9.24944	0	0	0	
+1.502	-0.997634	-0.548636	9.25736	0	0	0	
+1.503	-0.997703	-0.54071	9.26529	0	0	0	
+1.504	-0.99777	-0.532783	9.27322	0	0	0	
+1.505	-0.997836	-0.524853	9.28115	0	0	0	
+1.506	-0.997901	-0.516921	9.28908	0	0	0	
+1.507	-0.997966	-0.508987	9.29701	0	0	0	
+1.508	-0.998029	-0.501051	9.30495	0	0	0	
+1.509	-0.998091	-0.493113	9.31289	0	0	0	
+1.51	-0.998152	-0.485173	9.32083	0	0	0	
+1.511	-0.998213	-0.477231	9.32877	0	0	0	
+1.512	-0.998272	-0.469287	9.33671	0	0	0	
+1.513	-0.99833	-0.461342	9.34466	0	0	0	
+1.514	-0.998388	-0.453394	9.35261	0	0	0	
+1.515	-0.998444	-0.445445	9.36056	0	0	0	
+1.516	-0.998499	-0.437494	9.36851	0	0	0	
+1.517	-0.998553	-0.429541	9.37646	0	0	0	
+1.518	-0.998607	-0.421586	9.38441	0	0	0	
+1.519	-0.998659	-0.41363	9.39237	0	0	0	
+1.52	-0.99871	-0.405672	9.40033	0	0	0	
+1.521	-0.99876	-0.397712	9.40829	0	0	0	
+1.522	-0.99881	-0.389751	9.41625	0	0	0	
+1.523	-0.998858	-0.381789	9.42421	0	0	0	
+1.524	-0.998905	-0.373824	9.43218	0	0	0	
+1.525	-0.998952	-0.365859	9.44014	0	0	0	
+1.526	-0.998997	-0.357891	9.44811	0	0	0	
+1.527	-0.999041	-0.349923	9.45608	0	0	0	
+1.528	-0.999084	-0.341953	9.46405	0	0	0	
+1.529	-0.999127	-0.333981	9.47202	0	0	0	
+1.53	-0.999168	-0.326009	9.47999	0	0	0	
+1.531	-0.999208	-0.318035	9.48797	0	0	0	
+1.532	-0.999248	-0.310059	9.49594	0	0	0	
+1.533	-0.999286	-0.302083	9.50392	0	0	0	
+1.534	-0.999323	-0.294105	9.5119	0	0	0	
+1.535	-0.999359	-0.286126	9.51987	0	0	0	
+1.536	-0.999395	-0.278146	9.52785	0	0	0	
+1.537	-0.999429	-0.270165	9.53584	0	0	0	
+1.538	-0.999462	-0.262183	9.54382	0	0	0	
+1.539	-0.999495	-0.254199	9.5518	0	0	0	
+1.54	-0.999526	-0.246215	9.55979	0	0	0	
+1.541	-0.999556	-0.23823	9.56777	0	0	0	
+1.542	-0.999585	-0.230243	9.57576	0	0	0	
+1.543	-0.999614	-0.222256	9.58374	0	0	0	
+1.544	-0.999641	-0.214268	9.59173	0	0	0	
+1.545	-0.999667	-0.206279	9.59972	0	0	0	
+1.546	-0.999693	-0.198289	9.60771	0	0	0	
+1.547	-0.999717	-0.190299	9.6157	0	0	0	
+1.548	-0.99974	-0.182307	9.62369	0	0	0	
+1.549	-0.999762	-0.174315	9.63168	0	0	0	
+1.55	-0.999784	-0.166323	9.63968	0	0	0	
+1.551	-0.999804	-0.158329	9.64767	0	0	0	
+1.552	-0.999823	-0.150335	9.65566	0	0	0	
+1.553	-0.999842	-0.142341	9.66366	0	0	0	
+1.554	-0.999859	-0.134345	9.67165	0	0	0	
+1.555	-0.999875	-0.12635	9.67965	0	0	0	
+1.556	-0.999891	-0.118353	9.68765	0	0	0	
+1.557	-0.999905	-0.110357	9.69564	0	0	0	
+1.558	-0.999918	-0.102359	9.70364	0	0	0	
+1.559	-0.99993	-0.0943619	9.71164	0	0	0	
+1.56	-0.999942	-0.0863639	9.71964	0	0	0	
+1.561	-0.999952	-0.0783656	9.72763	0	0	0	
+1.562	-0.999961	-0.070367	9.73563	0	0	0	
+1.563	-0.99997	-0.0623681	9.74363	0	0	0	
+1.564	-0.999977	-0.0543689	9.75163	0	0	0	
+1.565	-0.999983	-0.0463696	9.75963	0	0	0	
+1.566	-0.999988	-0.03837	9.76763	0	0	0	
+1.567	-0.999993	-0.0303703	9.77563	0	0	0	
+1.568	-0.999996	-0.0223705	9.78363	0	0	0	
+1.569	-0.999998	-0.0143706	9.79163	0	0	0	
+1.57	-1	-0.00637061	9.79963	0	0	0	
+1.571	-1	0.00162939	9.80763	0	0	0	
+1.572	-0.999999	0.00962938	9.81563	0	0	0	
+1.573	-0.999998	0.0176293	9.82363	0	0	0	
+1.574	-0.999995	0.0256292	9.83163	0	0	0	
+1.575	-0.999991	0.033629	9.83963	0	0	0	
+1.576	-0.999986	0.0416286	9.84763	0	0	0	
+1.577	-0.999981	0.0496281	9.85563	0	0	0	
+1.578	-0.999974	0.0576274	9.86363	0	0	0	
+1.579	-0.999966	0.0656264	9.87163	0	0	0	
+1.58	-0.999958	0.0736252	9.87963	0	0	0	
+1.581	-0.999948	0.0816237	9.88762	0	0	0	
+1.582	-0.999937	0.0896219	9.89562	0	0	0	
+1.583	-0.999926	0.0976197	9.90362	0	0	0	
+1.584	-0.999913	0.105617	9.91162	0	0	0	
+1.585	-0.999899	0.113614	9.91961	0	0	0	
+1.586	-0.999884	0.121611	9.92761	0	0	0	
+1.587	-0.999869	0.129607	9.93561	0	0	0	
+1.588	-0.999852	0.137602	9.9436	0	0	0	
+1.589	-0.999834	0.145597	9.9516	0	0	0	
+1.59	-0.999816	0.153592	9.95959	0	0	0	
+1.591	-0.999796	0.161585	9.96759	0	0	0	
+1.592	-0.999775	0.169579	9.97558	0	0	0	
+1.593	-0.999754	0.177571	9.98357	0	0	0	
+1.594	-0.999731	0.185563	9.99156	0	0	0	
+1.595	-0.999707	0.193554	9.99955	0	0	0	
+1.596	-0.999682	0.201544	10.0075	0	0	0	
+1.597	-0.999657	0.209533	10.0155	0	0	0	
+1.598	-0.99963	0.217522	10.0235	0	0	0	
+1.599	-0.999602	0.22551	10.0315	0	0	0	
+1.6	-0.999574	0.233497	10.0395	0	0	0	
+1.601	-0.999544	0.241482	10.0475	0	0	0	
+1.602	-0.999513	0.249467	10.0555	0	0	0	
+1.603	-0.999482	0.257451	10.0635	0	0	0	
+1.604	-0.999449	0.265434	10.0714	0	0	0	
+1.605	-0.999415	0.273416	10.0794	0	0	0	
+1.606	-0.99938	0.281397	10.0874	0	0	0	
+1.607	-0.999345	0.289376	10.0954	0	0	0	
+1.608	-0.999308	0.297355	10.1034	0	0	0	
+1.609	-0.99927	0.305332	10.1113	0	0	0	
+1.61	-0.999232	0.313308	10.1193	0	0	0	
+1.611	-0.999192	0.321283	10.1273	0	0	0	
+1.612	-0.999151	0.329256	10.1353	0	0	0	
+1.613	-0.99911	0.337229	10.1432	0	0	0	
+1.614	-0.999067	0.345199	10.1512	0	0	0	
+1.615	-0.999023	0.353169	10.1592	0	0	0	
+1.616	-0.998978	0.361137	10.1671	0	0	0	
+1.617	-0.998933	0.369104	10.1751	0	0	0	
+1.618	-0.998886	0.377069	10.1831	0	0	0	
+1.619	-0.998838	0.385032	10.191	0	0	0	
+1.62	-0.99879	0.392994	10.199	0	0	0	
+1.621	-0.99874	0.400955	10.207	0	0	0	
+1.622	-0.998689	0.408914	10.2149	0	0	0	
+1.623	-0.998638	0.416871	10.2229	0	0	0	
+1.624	-0.998585	0.424827	10.2308	0	0	0	
+1.625	-0.998531	0.432781	10.2388	0	0	0	
+1.626	-0.998477	0.440733	10.2467	0	0	0	
+1.627	-0.998421	0.448683	10.2547	0	0	0	
+1.628	-0.998364	0.456632	10.2626	0	0	0	
+1.629	-0.998307	0.464578	10.2706	0	0	0	
+1.63	-0.998248	0.472523	10.2785	0	0	0	
+1.631	-0.998188	0.480466	10.2865	0	0	0	
+1.632	-0.998128	0.488408	10.2944	0	0	0	
+1.633	-0.998066	0.496347	10.3023	0	0	0	
+1.634	-0.998003	0.504284	10.3103	0	0	0	
+1.635	-0.99794	0.512219	10.3182	0	0	0	
+1.636	-0.997875	0.520152	10.3262	0	0	0	
+1.637	-0.997809	0.528083	10.3341	0	0	0	
+1.638	-0.997743	0.536012	10.342	0	0	0	
+1.639	-0.997675	0.543939	10.3499	0	0	0	
+1.64	-0.997606	0.551863	10.3579	0	0	0	
+1.641	-0.997537	0.559786	10.3658	0	0	0	
+1.642	-0.997466	0.567706	10.3737	0	0	0	
+1.643	-0.997394	0.575624	10.3816	0	0	0	
+1.644	-0.997322	0.583539	10.3895	0	0	0	
+1.645	-0.997248	0.591453	10.3975	0	0	0	
+1.646	-0.997174	0.599364	10.4054	0	0	0	
+1.647	-0.997098	0.607272	10.4133	0	0	0	
+1.648	-0.997021	0.615178	10.4212	0	0	0	
+1.649	-0.996944	0.623082	10.4291	0	0	0	
+1.65	-0.996865	0.630983	10.437	0	0	0	
+1.651	-0.996785	0.638881	10.4449	0	0	0	
+1.652	-0.996705	0.646777	10.4528	0	0	0	
+1.653	-0.996623	0.654671	10.4607	0	0	0	
+1.654	-0.996541	0.662562	10.4686	0	0	0	
+1.655	-0.996457	0.67045	10.4764	0	0	0	
+1.656	-0.996372	0.678335	10.4843	0	0	0	
+1.657	-0.996287	0.686218	10.4922	0	0	0	
+1.658	-0.9962	0.694098	10.5001	0	0	0	
+1.659	-0.996113	0.701975	10.508	0	0	0	
+1.66	-0.996024	0.70985	10.5158	0	0	0	
+1.661	-0.995934	0.717721	10.5237	0	0	0	
+1.662	-0.995844	0.72559	10.5316	0	0	0	
+1.663	-0.995752	0.733456	10.5395	0	0	0	
+1.664	-0.99566	0.741319	10.5473	0	0	0	
+1.665	-0.995566	0.749179	10.5552	0	0	0	
+1.666	-0.995472	0.757036	10.563	0	0	0	
+1.667	-0.995376	0.764889	10.5709	0	0	0	
+1.668	-0.995279	0.77274	10.5787	0	0	0	
+1.669	-0.995182	0.780588	10.5866	0	0	0	
+1.67	-0.995083	0.788433	10.5944	0	0	0	
+1.671	-0.994984	0.796274	10.6023	0	0	0	
+1.672	-0.994883	0.804112	10.6101	0	0	0	
+1.673	-0.994782	0.811948	10.6179	0	0	0	
+1.674	-0.994679	0.819779	10.6258	0	0	0	
+1.675	-0.994576	0.827608	10.6336	0	0	0	
+1.676	-0.994471	0.835433	10.6414	0	0	0	
+1.677	-0.994366	0.843255	10.6493	0	0	0	
+1.678	-0.994259	0.851074	10.6571	0	0	0	
+1.679	-0.994152	0.858889	10.6649	0	0	0	
+1.68	-0.994043	0.8667	10.6727	0	0	0	
+1.681	-0.993934	0.874509	10.6805	0	0	0	
+1.682	-0.993823	0.882313	10.6883	0	0	0	
+1.683	-0.993712	0.890114	10.6961	0	0	0	
+1.684	-0.993599	0.897912	10.7039	0	0	0	
+1.685	-0.993486	0.905706	10.7117	0	0	0	
+1.686	-0.993371	0.913496	10.7195	0	0	0	
+1.687	-0.993256	0.921283	10.7273	0	0	0	
+1.688	-0.99314	0.929066	10.7351	0	0	0	
+1.689	-0.993022	0.936846	10.7428	0	0	0	
+1.69	-0.992904	0.944621	10.7506	0	0	0	
+1.691	-0.992784	0.952393	10.7584	0	0	0	
+1.692	-0.992664	0.960161	10.7662	0	0	0	
+1.693	-0.992542	0.967925	10.7739	0	0	0	
+1.694	-0.99242	0.975686	10.7817	0	0	0	
+1.695	-0.992297	0.983442	10.7894	0	0	0	
+1.696	-0.992172	0.991194	10.7972	0	0	0	
+1.697	-0.992047	0.998943	10.8049	0	0	0	
+1.698	-0.991921	1.00669	10.8127	0	0	0	
+1.699	-0.991793	1.01443	10.8204	0	0	0	
+1.7	-0.991665	1.02216	10.8282	0	0	0	
+1.701	-0.991535	1.0299	10.8359	0	0	0	
+1.702	-0.991405	1.03762	10.8436	0	0	0	
+1.703	-0.991274	1.04535	10.8513	0	0	0	
+1.704	-0.991142	1.05307	10.8591	0	0	0	
+1.705	-0.991008	1.06078	10.8668	0	0	0	
+1.706	-0.990874	1.0685	10.8745	0	0	0	
+1.707	-0.990739	1.0762	10.8822	0	0	0	
+1.708	-0.990602	1.08391	10.8899	0	0	0	
+1.709	-0.990465	1.0916	10.8976	0	0	0	
+1.71	-0.990327	1.0993	10.9053	0	0	0	
+1.711	-0.990188	1.10699	10.913	0	0	0	
+1.712	-0.990047	1.11467	10.9207	0	0	0	
+1.713	-0.989906	1.12235	10.9284	0	0	0	
+1.714	-0.989764	1.13003	10.936	0	0	0	
+1.715	-0.989621	1.1377	10.9437	0	0	0	
+1.716	-0.989476	1.14537	10.9514	0	0	0	
+1.717	-0.989331	1.15303	10.959	0	0	0	
+1.718	-0.989185	1.16069	10.9667	0	0	0	
+1.719	-0.989038	1.16834	10.9743	0	0	0	
+1.72	-0.98889	1.17599	10.982	0	0	0	
+1.721	-0.988741	1.18364	10.9896	0	0	0	
+1.722	-0.98859	1.19128	10.9973	0	0	0	
+1.723	-0.988439	1.19891	11.0049	0	0	0	
+1.724	-0.988287	1.20654	11.0125	0	0	0	
+1.725	-0.988134	1.21417	11.0202	0	0	0	
+1.726	-0.98798	1.22179	11.0278	0	0	0	
+1.727	-0.987825	1.2294	11.0354	0	0	0	
+1.728	-0.987669	1.23701	11.043	0	0	0	
+1.729	-0.987512	1.24462	11.0506	0	0	0	
+1.73	-0.987354	1.25222	11.0582	0	0	0	
+1.731	-0.987195	1.25981	11.0658	0	0	0	
+1.732	-0.987035	1.2674	11.0734	0	0	0	
+1.733	-0.986874	1.27499	11.081	0	0	0	
+1.734	-0.986712	1.28257	11.0886	0	0	0	
+1.735	-0.986549	1.29014	11.0961	0	0	0	
+1.736	-0.986385	1.29771	11.1037	0	0	0	
+1.737	-0.98622	1.30528	11.1113	0	0	0	
+1.738	-0.986054	1.31284	11.1188	0	0	0	
+1.739	-0.985887	1.32039	11.1264	0	0	0	
+1.74	-0.985719	1.32794	11.1339	0	0	0	
+1.741	-0.98555	1.33548	11.1415	0	0	0	
+1.742	-0.98538	1.34302	11.149	0	0	0	
+1.743	-0.98521	1.35056	11.1566	0	0	0	
+1.744	-0.985038	1.35808	11.1641	0	0	0	
+1.745	-0.984865	1.36561	11.1716	0	0	0	
+1.746	-0.984691	1.37312	11.1791	0	0	0	
+1.747	-0.984516	1.38063	11.1866	0	0	0	
+1.748	-0.98434	1.38814	11.1941	0	0	0	
+1.749	-0.984164	1.39564	11.2016	0	0	0	
+1.75	-0.983986	1.40313	11.2091	0	0	0	
+1.751	-0.983807	1.41062	11.2166	0	0	0	
+1.752	-0.983627	1.4181	11.2241	0	0	0	
+1.753	-0.983447	1.42558	11.2316	0	0	0	
+1.754	-0.983265	1.43305	11.2391	0	0	0	
+1.755	-0.983082	1.44052	11.2465	0	0	0	
+1.756	-0.982899	1.44798	11.254	0	0	0	
+1.757	-0.982714	1.45544	11.2614	0	0	0	
+1.758	-0.982529	1.46288	11.2689	0	0	0	
+1.759	-0.982342	1.47033	11.2763	0	0	0	
+1.76	-0.982154	1.47776	11.2838	0	0	0	
+1.761	-0.981966	1.48519	11.2912	0	0	0	
+1.762	-0.981776	1.49262	11.2986	0	0	0	
+1.763	-0.981586	1.50004	11.306	0	0	0	
+1.764	-0.981394	1.50745	11.3135	0	0	0	
+1.765	-0.981202	1.51486	11.3209	0	0	0	
+1.766	-0.981008	1.52226	11.3283	0	0	0	
+1.767	-0.980814	1.52966	11.3357	0	0	0	
+1.768	-0.980618	1.53704	11.343	0	0	0	
+1.769	-0.980422	1.54443	11.3504	0	0	0	
+1.77	-0.980224	1.5518	11.3578	0	0	0	
+1.771	-0.980026	1.55917	11.3652	0	0	0	
+1.772	-0.979827	1.56654	11.3725	0	0	0	
+1.773	-0.979626	1.5739	11.3799	0	0	0	
+1.774	-0.979425	1.58125	11.3872	0	0	0	
+1.775	-0.979223	1.58859	11.3946	0	0	0	
+1.776	-0.97902	1.59593	11.4019	0	0	0	
+1.777	-0.978815	1.60326	11.4093	0	0	0	
+1.778	-0.97861	1.61059	11.4166	0	0	0	
+1.779	-0.978404	1.61791	11.4239	0	0	0	
+1.78	-0.978197	1.62522	11.4312	0	0	0	
+1.781	-0.977988	1.63253	11.4385	0	0	0	
+1.782	-0.977779	1.63983	11.4458	0	0	0	
+1.783	-0.977569	1.64712	11.4531	0	0	0	
+1.784	-0.977358	1.65441	11.4604	0	0	0	
+1.785	-0.977146	1.66169	11.4677	0	0	0	
+1.786	-0.976933	1.66896	11.475	0	0	0	
+1.787	-0.976719	1.67623	11.4822	0	0	0	
+1.788	-0.976504	1.68349	11.4895	0	0	0	
+1.789	-0.976288	1.69075	11.4967	0	0	0	
+1.79	-0.976071	1.69799	11.504	0	0	0	
+1.791	-0.975853	1.70523	11.5112	0	0	0	
+1.792	-0.975634	1.71247	11.5185	0	0	0	
+1.793	-0.975414	1.71969	11.5257	0	0	0	
+1.794	-0.975193	1.72691	11.5329	0	0	0	
+1.795	-0.974971	1.73412	11.5401	0	0	0	
+1.796	-0.974749	1.74133	11.5473	0	0	0	
+1.797	-0.974525	1.74853	11.5545	0	0	0	
+1.798	-0.9743	1.75572	11.5617	0	0	0	
+1.799	-0.974074	1.7629	11.5689	0	0	0	
+1.8	-0.973848	1.77008	11.5761	0	0	0	
+1.801	-0.97362	1.77725	11.5833	0	0	0	
+1.802	-0.973391	1.78442	11.5904	0	0	0	
+1.803	-0.973162	1.79157	11.5976	0	0	0	
+1.804	-0.972931	1.79872	11.6047	0	0	0	
+1.805	-0.972699	1.80586	11.6119	0	0	0	
+1.806	-0.972467	1.813	11.619	0	0	0	
+1.807	-0.972233	1.82013	11.6261	0	0	0	
+1.808	-0.971999	1.82725	11.6332	0	0	0	
+1.809	-0.971763	1.83436	11.6404	0	0	0	
+1.81	-0.971527	1.84146	11.6475	0	0	0	
+1.811	-0.97129	1.84856	11.6546	0	0	0	
+1.812	-0.971051	1.85565	11.6617	0	0	0	
+1.813	-0.970812	1.86274	11.6687	0	0	0	
+1.814	-0.970571	1.86981	11.6758	0	0	0	
+1.815	-0.97033	1.87688	11.6829	0	0	0	
+1.816	-0.970088	1.88394	11.6899	0	0	0	
+1.817	-0.969845	1.89099	11.697	0	0	0	
+1.818	-0.9696	1.89804	11.704	0	0	0	
+1.819	-0.969355	1.90508	11.7111	0	0	0	
+1.82	-0.969109	1.91211	11.7181	0	0	0	
+1.821	-0.968862	1.91913	11.7251	0	0	0	
+1.822	-0.968614	1.92615	11.7321	0	0	0	
+1.823	-0.968365	1.93315	11.7392	0	0	0	
+1.824	-0.968115	1.94015	11.7462	0	0	0	
+1.825	-0.967864	1.94715	11.7531	0	0	0	
+1.826	-0.967612	1.95413	11.7601	0	0	0	
+1.827	-0.967359	1.96111	11.7671	0	0	0	
+1.828	-0.967105	1.96808	11.7741	0	0	0	
+1.829	-0.96685	1.97504	11.781	0	0	0	
+1.83	-0.966594	1.98199	11.788	0	0	0	
+1.831	-0.966338	1.98893	11.7949	0	0	0	
+1.832	-0.96608	1.99587	11.8019	0	0	0	
+1.833	-0.965821	2.0028	11.8088	0	0	0	
+1.834	-0.965561	2.00972	11.8157	0	0	0	
+1.835	-0.965301	2.01663	11.8226	0	0	0	
+1.836	-0.965039	2.02354	11.8295	0	0	0	
+1.837	-0.964777	2.03044	11.8364	0	0	0	
+1.838	-0.964513	2.03732	11.8433	0	0	0	
+1.839	-0.964248	2.0442	11.8502	0	0	0	
+1.84	-0.963983	2.05108	11.8571	0	0	0	
+1.841	-0.963717	2.05794	11.8639	0	0	0	
+1.842	-0.963449	2.0648	11.8708	0	0	0	
+1.843	-0.963181	2.07164	11.8776	0	0	0	
+1.844	-0.962911	2.07848	11.8845	0	0	0	
+1.845	-0.962641	2.08532	11.8913	0	0	0	
+1.846	-0.96237	2.09214	11.8981	0	0	0	
+1.847	-0.962098	2.09895	11.905	0	0	0	
+1.848	-0.961824	2.10576	11.9118	0	0	0	
+1.849	-0.96155	2.11256	11.9186	0	0	0	
+1.85	-0.961275	2.11934	11.9253	0	0	0	
+1.851	-0.960999	2.12613	11.9321	0	0	0	
+1.852	-0.960722	2.1329	11.9389	0	0	0	
+1.853	-0.960444	2.13966	11.9457	0	0	0	
+1.854	-0.960165	2.14642	11.9524	0	0	0	
+1.855	-0.959885	2.15316	11.9592	0	0	0	
+1.856	-0.959604	2.1599	11.9659	0	0	0	
+1.857	-0.959323	2.16663	11.9726	0	0	0	
+1.858	-0.95904	2.17335	11.9793	0	0	0	
+1.859	-0.958756	2.18006	11.9861	0	0	0	
+1.86	-0.958471	2.18676	11.9928	0	0	0	
+1.861	-0.958186	2.19346	11.9995	0	0	0	
+1.862	-0.957899	2.20014	12.0061	0	0	0	
+1.863	-0.957611	2.20682	12.0128	0	0	0	
+1.864	-0.957323	2.21349	12.0195	0	0	0	
+1.865	-0.957033	2.22015	12.0261	0	0	0	
+1.866	-0.956743	2.2268	12.0328	0	0	0	
+1.867	-0.956451	2.23344	12.0394	0	0	0	
+1.868	-0.956159	2.24007	12.0461	0	0	0	
+1.869	-0.955866	2.24669	12.0527	0	0	0	
+1.87	-0.955572	2.25331	12.0593	0	0	0	
+1.871	-0.955276	2.25991	12.0659	0	0	0	
+1.872	-0.95498	2.26651	12.0725	0	0	0	
+1.873	-0.954683	2.2731	12.0791	0	0	0	
+1.874	-0.954385	2.27968	12.0857	0	0	0	
+1.875	-0.954086	2.28625	12.0922	0	0	0	
+1.876	-0.953786	2.29281	12.0988	0	0	0	
+1.877	-0.953485	2.29936	12.1054	0	0	0	
+1.878	-0.953183	2.3059	12.1119	0	0	0	
+1.879	-0.95288	2.31243	12.1184	0	0	0	
+1.88	-0.952576	2.31895	12.125	0	0	0	
+1.881	-0.952271	2.32547	12.1315	0	0	0	
+1.882	-0.951966	2.33197	12.138	0	0	0	
+1.883	-0.951659	2.33847	12.1445	0	0	0	
+1.884	-0.951351	2.34495	12.151	0	0	0	
+1.885	-0.951043	2.35143	12.1574	0	0	0	
+1.886	-0.950733	2.3579	12.1639	0	0	0	
+1.887	-0.950423	2.36435	12.1704	0	0	0	
+1.888	-0.950111	2.3708	12.1768	0	0	0	
+1.889	-0.949799	2.37724	12.1832	0	0	0	
+1.89	-0.949486	2.38367	12.1897	0	0	0	
+1.891	-0.949171	2.39009	12.1961	0	0	0	
+1.892	-0.948856	2.3965	12.2025	0	0	0	
+1.893	-0.94854	2.4029	12.2089	0	0	0	
+1.894	-0.948223	2.40929	12.2153	0	0	0	
+1.895	-0.947905	2.41567	12.2217	0	0	0	
+1.896	-0.947586	2.42204	12.228	0	0	0	
+1.897	-0.947266	2.4284	12.2344	0	0	0	
+1.898	-0.946945	2.43476	12.2408	0	0	0	
+1.899	-0.946623	2.4411	12.2471	0	0	0	
+1.9	-0.9463	2.44743	12.2534	0	0	0	
+1.901	-0.945976	2.45375	12.2598	0	0	0	
+1.902	-0.945652	2.46007	12.2661	0	0	0	
+1.903	-0.945326	2.46637	12.2724	0	0	0	
+1.904	-0.944999	2.47266	12.2787	0	0	0	
+1.905	-0.944672	2.47895	12.2849	0	0	0	
+1.906	-0.944343	2.48522	12.2912	0	0	0	
+1.907	-0.944014	2.49148	12.2975	0	0	0	
+1.908	-0.943684	2.49774	12.3037	0	0	0	
+1.909	-0.943352	2.50398	12.31	0	0	0	
+1.91	-0.94302	2.51022	12.3162	0	0	0	
+1.911	-0.942687	2.51644	12.3224	0	0	0	
+1.912	-0.942353	2.52265	12.3287	0	0	0	
+1.913	-0.942017	2.52886	12.3349	0	0	0	
+1.914	-0.941681	2.53505	12.341	0	0	0	
+1.915	-0.941344	2.54123	12.3472	0	0	0	
+1.916	-0.941007	2.54741	12.3534	0	0	0	
+1.917	-0.940668	2.55357	12.3596	0	0	0	
+1.918	-0.940328	2.55972	12.3657	0	0	0	
+1.919	-0.939987	2.56586	12.3719	0	0	0	
+1.92	-0.939645	2.57199	12.378	0	0	0	
+1.921	-0.939303	2.57812	12.3841	0	0	0	
+1.922	-0.938959	2.58423	12.3902	0	0	0	
+1.923	-0.938615	2.59033	12.3963	0	0	0	
+1.924	-0.938269	2.59642	12.4024	0	0	0	
+1.925	-0.937923	2.6025	12.4085	0	0	0	
+1.926	-0.937576	2.60857	12.4146	0	0	0	
+1.927	-0.937227	2.61463	12.4206	0	0	0	
+1.928	-0.936878	2.62068	12.4267	0	0	0	
+1.929	-0.936528	2.62672	12.4327	0	0	0	
+1.93	-0.936177	2.63275	12.4387	0	0	0	
+1.931	-0.935825	2.63876	12.4448	0	0	0	
+1.932	-0.935472	2.64477	12.4508	0	0	0	
+1.933	-0.935118	2.65077	12.4568	0	0	0	
+1.934	-0.934763	2.65675	12.4628	0	0	0	
+1.935	-0.934408	2.66273	12.4687	0	0	0	
+1.936	-0.934051	2.66869	12.4747	0	0	0	
+1.937	-0.933693	2.67465	12.4806	0	0	0	
+1.938	-0.933335	2.68059	12.4866	0	0	0	
+1.939	-0.932975	2.68652	12.4925	0	0	0	
+1.94	-0.932615	2.69244	12.4984	0	0	0	
+1.941	-0.932254	2.69835	12.5044	0	0	0	
+1.942	-0.931891	2.70425	12.5103	0	0	0	
+1.943	-0.931528	2.71014	12.5161	0	0	0	
+1.944	-0.931164	2.71602	12.522	0	0	0	
+1.945	-0.930799	2.72189	12.5279	0	0	0	
+1.946	-0.930433	2.72775	12.5337	0	0	0	
+1.947	-0.930066	2.73359	12.5396	0	0	0	
+1.948	-0.929698	2.73943	12.5454	0	0	0	
+1.949	-0.929329	2.74525	12.5513	0	0	0	
+1.95	-0.92896	2.75106	12.5571	0	0	0	
+1.951	-0.928589	2.75687	12.5629	0	0	0	
+1.952	-0.928217	2.76266	12.5687	0	0	0	
+1.953	-0.927845	2.76844	12.5744	0	0	0	
+1.954	-0.927472	2.77421	12.5802	0	0	0	
+1.955	-0.927097	2.77996	12.586	0	0	0	
+1.956	-0.926722	2.78571	12.5917	0	0	0	
+1.957	-0.926346	2.79145	12.5974	0	0	0	
+1.958	-0.925969	2.79717	12.6032	0	0	0	
+1.959	-0.925591	2.80288	12.6089	0	0	0	
+1.96	-0.925212	2.80859	12.6146	0	0	0	
+1.961	-0.924832	2.81428	12.6203	0	0	0	
+1.962	-0.924451	2.81996	12.626	0	0	0	
+1.963	-0.924069	2.82562	12.6316	0	0	0	
+1.964	-0.923686	2.83128	12.6373	0	0	0	
+1.965	-0.923303	2.83693	12.6429	0	0	0	
+1.966	-0.922918	2.84256	12.6486	0	0	0	
+1.967	-0.922533	2.84818	12.6542	0	0	0	
+1.968	-0.922146	2.85379	12.6598	0	0	0	
+1.969	-0.921759	2.85939	12.6654	0	0	0	
+1.97	-0.921371	2.86498	12.671	0	0	0	
+1.971	-0.920982	2.87056	12.6766	0	0	0	
+1.972	-0.920592	2.87612	12.6821	0	0	0	
+1.973	-0.920201	2.88168	12.6877	0	0	0	
+1.974	-0.919809	2.88722	12.6932	0	0	0	
+1.975	-0.919416	2.89275	12.6988	0	0	0	
+1.976	-0.919022	2.89827	12.7043	0	0	0	
+1.977	-0.918627	2.90378	12.7098	0	0	0	
+1.978	-0.918232	2.90928	12.7153	0	0	0	
+1.979	-0.917835	2.91476	12.7208	0	0	0	
+1.98	-0.917438	2.92023	12.7262	0	0	0	
+1.981	-0.91704	2.92569	12.7317	0	0	0	
+1.982	-0.91664	2.93114	12.7371	0	0	0	
+1.983	-0.91624	2.93658	12.7426	0	0	0	
+1.984	-0.915839	2.94201	12.748	0	0	0	
+1.985	-0.915437	2.94742	12.7534	0	0	0	
+1.986	-0.915034	2.95282	12.7588	0	0	0	
+1.987	-0.91463	2.95822	12.7642	0	0	0	
+1.988	-0.914226	2.96359	12.7696	0	0	0	
+1.989	-0.91382	2.96896	12.775	0	0	0	
+1.99	-0.913413	2.97432	12.7803	0	0	0	
+1.991	-0.913006	2.97966	12.7857	0	0	0	
+1.992	-0.912597	2.98499	12.791	0	0	0	
+1.993	-0.912188	2.99031	12.7963	0	0	0	
+1.994	-0.911778	2.99562	12.8016	0	0	0	
+1.995	-0.911367	3.00091	12.8069	0	0	0	
+1.996	-0.910955	3.0062	12.8122	0	0	0	
+1.997	-0.910542	3.01147	12.8175	0	0	0	
+1.998	-0.910128	3.01673	12.8227	0	0	0	
+1.999	-0.909713	3.02197	12.828	0	0	0	
+2	-0.909297	3.02721	12.8332	0	0	0	
+2.001	-0.908881	3.03243	12.8384	0	0	0	
+2.002	-0.908463	3.03764	12.8436	0	0	0	
+2.003	-0.908045	3.04284	12.8488	0	0	0	
+2.004	-0.907626	3.04803	12.854	0	0	0	
+2.005	-0.907205	3.0532	12.8592	0	0	0	
+2.006	-0.906784	3.05837	12.8644	0	0	0	
+2.007	-0.906362	3.06352	12.8695	0	0	0	
+2.008	-0.905939	3.06865	12.8747	0	0	0	
+2.009	-0.905515	3.07378	12.8798	0	0	0	
+2.01	-0.905091	3.07889	12.8849	0	0	0	
+2.011	-0.904665	3.08399	12.89	0	0	0	
+2.012	-0.904238	3.08908	12.8951	0	0	0	
+2.013	-0.903811	3.09416	12.9002	0	0	0	
+2.014	-0.903382	3.09922	12.9052	0	0	0	
+2.015	-0.902953	3.10427	12.9103	0	0	0	
+2.016	-0.902523	3.10931	12.9153	0	0	0	
+2.017	-0.902092	3.11434	12.9203	0	0	0	
+2.018	-0.90166	3.11935	12.9254	0	0	0	
+2.019	-0.901227	3.12435	12.9304	0	0	0	
+2.02	-0.900793	3.12934	12.9353	0	0	0	
+2.021	-0.900358	3.13432	12.9403	0	0	0	
+2.022	-0.899923	3.13928	12.9453	0	0	0	
+2.023	-0.899486	3.14424	12.9502	0	0	0	
+2.024	-0.899049	3.14917	12.9552	0	0	0	
+2.025	-0.898611	3.1541	12.9601	0	0	0	
+2.026	-0.898172	3.15901	12.965	0	0	0	
+2.027	-0.897731	3.16392	12.9699	0	0	0	
+2.028	-0.89729	3.1688	12.9748	0	0	0	
+2.029	-0.896849	3.17368	12.9797	0	0	0	
+2.03	-0.896406	3.17854	12.9845	0	0	0	
+2.031	-0.895962	3.18339	12.9894	0	0	0	
+2.032	-0.895517	3.18823	12.9942	0	0	0	
+2.033	-0.895072	3.19306	12.9991	0	0	0	
+2.034	-0.894626	3.19787	13.0039	0	0	0	
+2.035	-0.894178	3.20267	13.0087	0	0	0	
+2.036	-0.89373	3.20745	13.0135	0	0	0	
+2.037	-0.893281	3.21223	13.0182	0	0	0	
+2.038	-0.892831	3.21699	13.023	0	0	0	
+2.039	-0.89238	3.22174	13.0277	0	0	0	
+2.04	-0.891929	3.22647	13.0325	0	0	0	
+2.041	-0.891476	3.23119	13.0372	0	0	0	
+2.042	-0.891023	3.2359	13.0419	0	0	0	
+2.043	-0.890568	3.2406	13.0466	0	0	0	
+2.044	-0.890113	3.24528	13.0513	0	0	0	
+2.045	-0.889657	3.24995	13.056	0	0	0	
+2.046	-0.8892	3.25461	13.0606	0	0	0	
+2.047	-0.888742	3.25925	13.0653	0	0	0	
+2.048	-0.888283	3.26389	13.0699	0	0	0	
+2.049	-0.887823	3.2685	13.0745	0	0	0	
+2.05	-0.887362	3.27311	13.0791	0	0	0	
+2.051	-0.886901	3.2777	13.0837	0	0	0	
+2.052	-0.886438	3.28228	13.0883	0	0	0	
+2.053	-0.885975	3.28685	13.0928	0	0	0	
+2.054	-0.885511	3.2914	13.0974	0	0	0	
+2.055	-0.885046	3.29594	13.1019	0	0	0	
+2.056	-0.88458	3.30046	13.1065	0	0	0	
+2.057	-0.884113	3.30498	13.111	0	0	0	
+2.058	-0.883645	3.30948	13.1155	0	0	0	
+2.059	-0.883177	3.31396	13.12	0	0	0	
+2.06	-0.882707	3.31844	13.1244	0	0	0	
+2.061	-0.882237	3.3229	13.1289	0	0	0	
+2.062	-0.881766	3.32734	13.1333	0	0	0	
+2.063	-0.881294	3.33178	13.1378	0	0	0	
+2.064	-0.880821	3.3362	13.1422	0	0	0	
+2.065	-0.880347	3.3406	13.1466	0	0	0	
+2.066	-0.879872	3.345	13.151	0	0	0	
+2.067	-0.879396	3.34938	13.1554	0	0	0	
+2.068	-0.87892	3.35374	13.1597	0	0	0	
+2.069	-0.878442	3.3581	13.1641	0	0	0	
+2.07	-0.877964	3.36244	13.1684	0	0	0	
+2.071	-0.877485	3.36676	13.1728	0	0	0	
+2.072	-0.877005	3.37108	13.1771	0	0	0	
+2.073	-0.876524	3.37538	13.1814	0	0	0	
+2.074	-0.876042	3.37966	13.1857	0	0	0	
+2.075	-0.875559	3.38393	13.1899	0	0	0	
+2.076	-0.875076	3.38819	13.1942	0	0	0	
+2.077	-0.874591	3.39244	13.1984	0	0	0	
+2.078	-0.874106	3.39667	13.2027	0	0	0	
+2.079	-0.87362	3.40089	13.2069	0	0	0	
+2.08	-0.873133	3.40509	13.2111	0	0	0	
+2.081	-0.872645	3.40928	13.2153	0	0	0	
+2.082	-0.872156	3.41346	13.2195	0	0	0	
+2.083	-0.871667	3.41763	13.2236	0	0	0	
+2.084	-0.871176	3.42178	13.2278	0	0	0	
+2.085	-0.870685	3.42591	13.2319	0	0	0	
+2.086	-0.870192	3.43003	13.236	0	0	0	
+2.087	-0.869699	3.43414	13.2401	0	0	0	
+2.088	-0.869205	3.43824	13.2442	0	0	0	
+2.089	-0.86871	3.44232	13.2483	0	0	0	
+2.09	-0.868215	3.44639	13.2524	0	0	0	
+2.091	-0.867718	3.45044	13.2564	0	0	0	
+2.092	-0.86722	3.45448	13.2605	0	0	0	
+2.093	-0.866722	3.45851	13.2645	0	0	0	
+2.094	-0.866223	3.46252	13.2685	0	0	0	
+2.095	-0.865723	3.46652	13.2725	0	0	0	
+2.096	-0.865222	3.4705	13.2765	0	0	0	
+2.097	-0.86472	3.47447	13.2805	0	0	0	
+2.098	-0.864217	3.47843	13.2844	0	0	0	
+2.099	-0.863714	3.48237	13.2884	0	0	0	
+2.1	-0.863209	3.4863	13.2923	0	0	0	
+2.101	-0.862704	3.49022	13.2962	0	0	0	
+2.102	-0.862198	3.49412	13.3001	0	0	0	
+2.103	-0.861691	3.49801	13.304	0	0	0	
+2.104	-0.861183	3.50188	13.3079	0	0	0	
+2.105	-0.860674	3.50574	13.3117	0	0	0	
+2.106	-0.860165	3.50958	13.3156	0	0	0	
+2.107	-0.859654	3.51342	13.3194	0	0	0	
+2.108	-0.859143	3.51723	13.3232	0	0	0	
+2.109	-0.858631	3.52104	13.327	0	0	0	
+2.11	-0.858118	3.52482	13.3308	0	0	0	
+2.111	-0.857604	3.5286	13.3346	0	0	0	
+2.112	-0.857089	3.53236	13.3384	0	0	0	
+2.113	-0.856574	3.53611	13.3421	0	0	0	
+2.114	-0.856057	3.53984	13.3458	0	0	0	
+2.115	-0.85554	3.54356	13.3496	0	0	0	
+2.116	-0.855022	3.54726	13.3533	0	0	0	
+2.117	-0.854503	3.55095	13.357	0	0	0	
+2.118	-0.853983	3.55463	13.3606	0	0	0	
+2.119	-0.853462	3.55829	13.3643	0	0	0	
+2.12	-0.85294	3.56194	13.3679	0	0	0	
+2.121	-0.852418	3.56557	13.3716	0	0	0	
+2.122	-0.851895	3.56919	13.3752	0	0	0	
+2.123	-0.851371	3.57279	13.3788	0	0	0	
+2.124	-0.850846	3.57638	13.3824	0	0	0	
+2.125	-0.85032	3.57996	13.386	0	0	0	
+2.126	-0.849793	3.58352	13.3895	0	0	0	
+2.127	-0.849266	3.58707	13.3931	0	0	0	
+2.128	-0.848737	3.5906	13.3966	0	0	0	
+2.129	-0.848208	3.59412	13.4001	0	0	0	
+2.13	-0.847678	3.59762	13.4036	0	0	0	
+2.131	-0.847147	3.60111	13.4071	0	0	0	
+2.132	-0.846615	3.60459	13.4106	0	0	0	
+2.133	-0.846082	3.60805	13.414	0	0	0	
+2.134	-0.845549	3.61149	13.4175	0	0	0	
+2.135	-0.845015	3.61493	13.4209	0	0	0	
+2.136	-0.84448	3.61834	13.4243	0	0	0	
+2.137	-0.843944	3.62175	13.4277	0	0	0	
+2.138	-0.843407	3.62514	13.4311	0	0	0	
+2.139	-0.842869	3.62851	13.4345	0	0	0	
+2.14	-0.84233	3.63187	13.4379	0	0	0	
+2.141	-0.841791	3.63521	13.4412	0	0	0	
+2.142	-0.841251	3.63854	13.4445	0	0	0	
+2.143	-0.84071	3.64186	13.4479	0	0	0	
+2.144	-0.840168	3.64516	13.4512	0	0	0	
+2.145	-0.839625	3.64845	13.4544	0	0	0	
+2.146	-0.839082	3.65172	13.4577	0	0	0	
+2.147	-0.838537	3.65498	13.461	0	0	0	
+2.148	-0.837992	3.65822	13.4642	0	0	0	
+2.149	-0.837446	3.66145	13.4675	0	0	0	
+2.15	-0.836899	3.66466	13.4707	0	0	0	
+2.151	-0.836351	3.66786	13.4739	0	0	0	
+2.152	-0.835802	3.67105	13.477	0	0	0	
+2.153	-0.835253	3.67422	13.4802	0	0	0	
+2.154	-0.834703	3.67737	13.4834	0	0	0	
+2.155	-0.834152	3.68051	13.4865	0	0	0	
+2.156	-0.8336	3.68364	13.4896	0	0	0	
+2.157	-0.833047	3.68675	13.4927	0	0	0	
+2.158	-0.832493	3.68984	13.4958	0	0	0	
+2.159	-0.831939	3.69293	13.4989	0	0	0	
+2.16	-0.831383	3.69599	13.502	0	0	0	
+2.161	-0.830827	3.69904	13.505	0	0	0	
+2.162	-0.83027	3.70208	13.5081	0	0	0	
+2.163	-0.829713	3.7051	13.5111	0	0	0	
+2.164	-0.829154	3.70811	13.5141	0	0	0	
+2.165	-0.828595	3.7111	13.5171	0	0	0	
+2.166	-0.828034	3.71408	13.5201	0	0	0	
+2.167	-0.827473	3.71704	13.523	0	0	0	
+2.168	-0.826911	3.71999	13.526	0	0	0	
+2.169	-0.826349	3.72292	13.5289	0	0	0	
+2.17	-0.825785	3.72584	13.5318	0	0	0	
+2.171	-0.825221	3.72875	13.5347	0	0	0	
+2.172	-0.824655	3.73163	13.5376	0	0	0	
+2.173	-0.824089	3.73451	13.5405	0	0	0	
+2.174	-0.823522	3.73737	13.5434	0	0	0	
+2.175	-0.822955	3.74021	13.5462	0	0	0	
+2.176	-0.822386	3.74304	13.549	0	0	0	
+2.177	-0.821817	3.74585	13.5519	0	0	0	
+2.178	-0.821247	3.74865	13.5547	0	0	0	
+2.179	-0.820676	3.75143	13.5574	0	0	0	
+2.18	-0.820104	3.7542	13.5602	0	0	0	
+2.181	-0.819531	3.75696	13.563	0	0	0	
+2.182	-0.818958	3.7597	13.5657	0	0	0	
+2.183	-0.818384	3.76242	13.5684	0	0	0	
+2.184	-0.817809	3.76513	13.5711	0	0	0	
+2.185	-0.817233	3.76782	13.5738	0	0	0	
+2.186	-0.816656	3.7705	13.5765	0	0	0	
+2.187	-0.816078	3.77316	13.5792	0	0	0	
+2.188	-0.8155	3.77581	13.5818	0	0	0	
+2.189	-0.814921	3.77844	13.5844	0	0	0	
+2.19	-0.814341	3.78106	13.5871	0	0	0	
+2.191	-0.81376	3.78366	13.5897	0	0	0	
+2.192	-0.813178	3.78625	13.5923	0	0	0	
+2.193	-0.812596	3.78883	13.5948	0	0	0	
+2.194	-0.812013	3.79138	13.5974	0	0	0	
+2.195	-0.811429	3.79392	13.5999	0	0	0	
+2.196	-0.810844	3.79645	13.6025	0	0	0	
+2.197	-0.810258	3.79896	13.605	0	0	0	
+2.198	-0.809672	3.80146	13.6075	0	0	0	
+2.199	-0.809085	3.80394	13.6099	0	0	0	
+2.2	-0.808496	3.80641	13.6124	0	0	0	
+2.201	-0.807907	3.80886	13.6149	0	0	0	
+2.202	-0.807318	3.8113	13.6173	0	0	0	
+2.203	-0.806727	3.81372	13.6197	0	0	0	
+2.204	-0.806136	3.81612	13.6221	0	0	0	
+2.205	-0.805544	3.81851	13.6245	0	0	0	
+2.206	-0.804951	3.82089	13.6269	0	0	0	
+2.207	-0.804357	3.82325	13.6292	0	0	0	
+2.208	-0.803763	3.82559	13.6316	0	0	0	
+2.209	-0.803167	3.82792	13.6339	0	0	0	
+2.21	-0.802571	3.83023	13.6362	0	0	0	
+2.211	-0.801974	3.83253	13.6385	0	0	0	
+2.212	-0.801376	3.83481	13.6408	0	0	0	
+2.213	-0.800778	3.83708	13.6431	0	0	0	
+2.214	-0.800178	3.83933	13.6453	0	0	0	
+2.215	-0.799578	3.84157	13.6476	0	0	0	
+2.216	-0.798977	3.84379	13.6498	0	0	0	
+2.217	-0.798376	3.846	13.652	0	0	0	
+2.218	-0.797773	3.84819	13.6542	0	0	0	
+2.219	-0.79717	3.85036	13.6564	0	0	0	
+2.22	-0.796565	3.85252	13.6585	0	0	0	
+2.221	-0.795961	3.85467	13.6607	0	0	0	
+2.222	-0.795355	3.8568	13.6628	0	0	0	
+2.223	-0.794748	3.85891	13.6649	0	0	0	
+2.224	-0.794141	3.86101	13.667	0	0	0	
+2.225	-0.793533	3.86309	13.6691	0	0	0	
+2.226	-0.792924	3.86516	13.6712	0	0	0	
+2.227	-0.792314	3.86721	13.6732	0	0	0	
+2.228	-0.791704	3.86925	13.6752	0	0	0	
+2.229	-0.791092	3.87127	13.6773	0	0	0	
+2.23	-0.79048	3.87327	13.6793	0	0	0	
+2.231	-0.789867	3.87526	13.6813	0	0	0	
+2.232	-0.789254	3.87724	13.6832	0	0	0	
+2.233	-0.788639	3.8792	13.6852	0	0	0	
+2.234	-0.788024	3.88114	13.6871	0	0	0	
+2.235	-0.787408	3.88307	13.6891	0	0	0	
+2.236	-0.786791	3.88498	13.691	0	0	0	
+2.237	-0.786173	3.88688	13.6929	0	0	0	
+2.238	-0.785555	3.88876	13.6948	0	0	0	
+2.239	-0.784936	3.89063	13.6966	0	0	0	
+2.24	-0.784316	3.89248	13.6985	0	0	0	
+2.241	-0.783695	3.89431	13.7003	0	0	0	
+2.242	-0.783074	3.89613	13.7021	0	0	0	
+2.243	-0.782451	3.89793	13.7039	0	0	0	
+2.244	-0.781828	3.89972	13.7057	0	0	0	
+2.245	-0.781204	3.90149	13.7075	0	0	0	
+2.246	-0.78058	3.90325	13.7092	0	0	0	
+2.247	-0.779954	3.90499	13.711	0	0	0	
+2.248	-0.779328	3.90672	13.7127	0	0	0	
+2.249	-0.778701	3.90843	13.7144	0	0	0	
+2.25	-0.778073	3.91012	13.7161	0	0	0	
+2.251	-0.777445	3.9118	13.7178	0	0	0	
+2.252	-0.776815	3.91346	13.7195	0	0	0	
+2.253	-0.776185	3.91511	13.7211	0	0	0	
+2.254	-0.775554	3.91674	13.7227	0	0	0	
+2.255	-0.774923	3.91836	13.7244	0	0	0	
+2.256	-0.77429	3.91996	13.726	0	0	0	
+2.257	-0.773657	3.92154	13.7275	0	0	0	
+2.258	-0.773023	3.92311	13.7291	0	0	0	
+2.259	-0.772388	3.92466	13.7307	0	0	0	
+2.26	-0.771753	3.9262	13.7322	0	0	0	
+2.261	-0.771116	3.92772	13.7337	0	0	0	
+2.262	-0.770479	3.92923	13.7352	0	0	0	
+2.263	-0.769841	3.93072	13.7367	0	0	0	
+2.264	-0.769203	3.93219	13.7382	0	0	0	
+2.265	-0.768563	3.93365	13.7397	0	0	0	
+2.266	-0.767923	3.9351	13.7411	0	0	0	
+2.267	-0.767282	3.93652	13.7425	0	0	0	
+2.268	-0.766641	3.93794	13.7439	0	0	0	
+2.269	-0.765998	3.93933	13.7453	0	0	0	
+2.27	-0.765355	3.94071	13.7467	0	0	0	
+2.271	-0.764711	3.94208	13.7481	0	0	0	
+2.272	-0.764066	3.94342	13.7494	0	0	0	
+2.273	-0.763421	3.94476	13.7508	0	0	0	
+2.274	-0.762774	3.94607	13.7521	0	0	0	
+2.275	-0.762127	3.94738	13.7534	0	0	0	
+2.276	-0.76148	3.94866	13.7547	0	0	0	
+2.277	-0.760831	3.94993	13.7559	0	0	0	
+2.278	-0.760182	3.95118	13.7572	0	0	0	
+2.279	-0.759532	3.95242	13.7584	0	0	0	
+2.28	-0.758881	3.95365	13.7596	0	0	0	
+2.281	-0.758229	3.95485	13.7609	0	0	0	
+2.282	-0.757577	3.95604	13.762	0	0	0	
+2.283	-0.756924	3.95722	13.7632	0	0	0	
+2.284	-0.75627	3.95838	13.7644	0	0	0	
+2.285	-0.755615	3.95952	13.7655	0	0	0	
+2.286	-0.75496	3.96065	13.7666	0	0	0	
+2.287	-0.754304	3.96176	13.7678	0	0	0	
+2.288	-0.753647	3.96285	13.7689	0	0	0	
+2.289	-0.752989	3.96393	13.7699	0	0	0	
+2.29	-0.752331	3.965	13.771	0	0	0	
+2.291	-0.751671	3.96605	13.772	0	0	0	
+2.292	-0.751012	3.96708	13.7731	0	0	0	
+2.293	-0.750351	3.96809	13.7741	0	0	0	
+2.294	-0.749689	3.96909	13.7751	0	0	0	
+2.295	-0.749027	3.97008	13.7761	0	0	0	
+2.296	-0.748364	3.97105	13.777	0	0	0	
+2.297	-0.747701	3.972	13.778	0	0	0	
+2.298	-0.747036	3.97294	13.7789	0	0	0	
+2.299	-0.746371	3.97386	13.7799	0	0	0	
+2.3	-0.745705	3.97476	13.7808	0	0	0	
+2.301	-0.745039	3.97565	13.7817	0	0	0	
+2.302	-0.744371	3.97653	13.7825	0	0	0	
+2.303	-0.743703	3.97738	13.7834	0	0	0	
+2.304	-0.743034	3.97823	13.7842	0	0	0	
+2.305	-0.742365	3.97905	13.7851	0	0	0	
+2.306	-0.741694	3.97986	13.7859	0	0	0	
+2.307	-0.741023	3.98065	13.7867	0	0	0	
+2.308	-0.740351	3.98143	13.7874	0	0	0	
+2.309	-0.739679	3.98219	13.7882	0	0	0	
+2.31	-0.739005	3.98294	13.7889	0	0	0	
+2.311	-0.738331	3.98367	13.7897	0	0	0	
+2.312	-0.737656	3.98438	13.7904	0	0	0	
+2.313	-0.736981	3.98508	13.7911	0	0	0	
+2.314	-0.736305	3.98577	13.7918	0	0	0	
+2.315	-0.735628	3.98643	13.7924	0	0	0	
+2.316	-0.73495	3.98708	13.7931	0	0	0	
+2.317	-0.734271	3.98772	13.7937	0	0	0	
+2.318	-0.733592	3.98834	13.7943	0	0	0	
+2.319	-0.732912	3.98894	13.7949	0	0	0	
+2.32	-0.732231	3.98952	13.7955	0	0	0	
+2.321	-0.73155	3.99009	13.7961	0	0	0	
+2.322	-0.730868	3.99065	13.7966	0	0	0	
+2.323	-0.730185	3.99119	13.7972	0	0	0	
+2.324	-0.729501	3.99171	13.7977	0	0	0	
+2.325	-0.728817	3.99222	13.7982	0	0	0	
+2.326	-0.728132	3.99271	13.7987	0	0	0	
+2.327	-0.727446	3.99318	13.7992	0	0	0	
+2.328	-0.72676	3.99364	13.7996	0	0	0	
+2.329	-0.726072	3.99409	13.8001	0	0	0	
+2.33	-0.725384	3.99451	13.8005	0	0	0	
+2.331	-0.724696	3.99492	13.8009	0	0	0	
+2.332	-0.724006	3.99532	13.8013	0	0	0	
+2.333	-0.723316	3.9957	13.8017	0	0	0	
+2.334	-0.722625	3.99606	13.8021	0	0	0	
+2.335	-0.721934	3.99641	13.8024	0	0	0	
+2.336	-0.721241	3.99674	13.8027	0	0	0	
+2.337	-0.720548	3.99705	13.8031	0	0	0	
+2.338	-0.719854	3.99735	13.8034	0	0	0	
+2.339	-0.71916	3.99764	13.8036	0	0	0	
+2.34	-0.718465	3.9979	13.8039	0	0	0	
+2.341	-0.717769	3.99815	13.8042	0	0	0	
+2.342	-0.717072	3.99839	13.8044	0	0	0	
+2.343	-0.716375	3.99861	13.8046	0	0	0	
+2.344	-0.715677	3.99881	13.8048	0	0	0	
+2.345	-0.714978	3.999	13.805	0	0	0	
+2.346	-0.714279	3.99917	13.8052	0	0	0	
+2.347	-0.713578	3.99932	13.8053	0	0	0	
+2.348	-0.712877	3.99946	13.8055	0	0	0	
+2.349	-0.712176	3.99959	13.8056	0	0	0	
+2.35	-0.711473	3.99969	13.8057	0	0	0	
+2.351	-0.71077	3.99978	13.8058	0	0	0	
+2.352	-0.710067	3.99986	13.8059	0	0	0	
+2.353	-0.709362	3.99992	13.8059	0	0	0	
+2.354	-0.708657	3.99996	13.806	0	0	0	
+2.355	-0.707951	3.99999	13.806	0	0	0	
+2.356	-0.707244	4	13.806	0	0	0	
+2.357	-0.706537	3.99999	13.806	0	0	0	
+2.358	-0.705829	3.99997	13.806	0	0	0	
+2.359	-0.70512	3.99994	13.8059	0	0	0	
+2.36	-0.704411	3.99988	13.8059	0	0	0	
+2.361	-0.703701	3.99982	13.8058	0	0	0	
+2.362	-0.70299	3.99973	13.8057	0	0	0	
+2.363	-0.702278	3.99963	13.8056	0	0	0	
+2.364	-0.701566	3.99951	13.8055	0	0	0	
+2.365	-0.700853	3.99938	13.8054	0	0	0	
+2.366	-0.700139	3.99923	13.8052	0	0	0	
+2.367	-0.699425	3.99907	13.8051	0	0	0	
+2.368	-0.69871	3.99889	13.8049	0	0	0	
+2.369	-0.697994	3.99869	13.8047	0	0	0	
+2.37	-0.697278	3.99848	13.8045	0	0	0	
+2.371	-0.696561	3.99825	13.8042	0	0	0	
+2.372	-0.695843	3.998	13.804	0	0	0	
+2.373	-0.695124	3.99774	13.8037	0	0	0	
+2.374	-0.694405	3.99746	13.8035	0	0	0	
+2.375	-0.693685	3.99717	13.8032	0	0	0	
+2.376	-0.692964	3.99686	13.8029	0	0	0	
+2.377	-0.692243	3.99654	13.8025	0	0	0	
+2.378	-0.691521	3.9962	13.8022	0	0	0	
+2.379	-0.690798	3.99584	13.8018	0	0	0	
+2.38	-0.690075	3.99547	13.8015	0	0	0	
+2.381	-0.689351	3.99508	13.8011	0	0	0	
+2.382	-0.688626	3.99467	13.8007	0	0	0	
+2.383	-0.687901	3.99425	13.8003	0	0	0	
+2.384	-0.687175	3.99382	13.7998	0	0	0	
+2.385	-0.686448	3.99336	13.7994	0	0	0	
+2.386	-0.68572	3.9929	13.7989	0	0	0	
+2.387	-0.684992	3.99241	13.7984	0	0	0	
+2.388	-0.684263	3.99191	13.7979	0	0	0	
+2.389	-0.683533	3.99139	13.7974	0	0	0	
+2.39	-0.682803	3.99086	13.7969	0	0	0	
+2.391	-0.682072	3.99031	13.7963	0	0	0	
+2.392	-0.681341	3.98975	13.7957	0	0	0	
+2.393	-0.680608	3.98917	13.7952	0	0	0	
+2.394	-0.679875	3.98857	13.7946	0	0	0	
+2.395	-0.679142	3.98796	13.794	0	0	0	
+2.396	-0.678407	3.98733	13.7933	0	0	0	
+2.397	-0.677672	3.98669	13.7927	0	0	0	
+2.398	-0.676937	3.98603	13.792	0	0	0	
+2.399	-0.6762	3.98535	13.7914	0	0	0	
+2.4	-0.675463	3.98466	13.7907	0	0	0	
+2.401	-0.674725	3.98395	13.79	0	0	0	
+2.402	-0.673987	3.98323	13.7892	0	0	0	
+2.403	-0.673248	3.98249	13.7885	0	0	0	
+2.404	-0.672508	3.98173	13.7877	0	0	0	
+2.405	-0.671768	3.98096	13.787	0	0	0	
+2.406	-0.671027	3.98017	13.7862	0	0	0	
+2.407	-0.670285	3.97937	13.7854	0	0	0	
+2.408	-0.669542	3.97855	13.7845	0	0	0	
+2.409	-0.668799	3.97771	13.7837	0	0	0	
+2.41	-0.668056	3.97686	13.7829	0	0	0	
+2.411	-0.667311	3.97599	13.782	0	0	0	
+2.412	-0.666566	3.97511	13.7811	0	0	0	
+2.413	-0.66582	3.97421	13.7802	0	0	0	
+2.414	-0.665074	3.9733	13.7793	0	0	0	
+2.415	-0.664327	3.97237	13.7784	0	0	0	
+2.416	-0.663579	3.97142	13.7774	0	0	0	
+2.417	-0.66283	3.97046	13.7765	0	0	0	
+2.418	-0.662081	3.96948	13.7755	0	0	0	
+2.419	-0.661332	3.96849	13.7745	0	0	0	
+2.42	-0.660581	3.96748	13.7735	0	0	0	
+2.421	-0.65983	3.96645	13.7724	0	0	0	
+2.422	-0.659078	3.96541	13.7714	0	0	0	
+2.423	-0.658326	3.96435	13.7703	0	0	0	
+2.424	-0.657573	3.96328	13.7693	0	0	0	
+2.425	-0.656819	3.96219	13.7682	0	0	0	
+2.426	-0.656065	3.96108	13.7671	0	0	0	
+2.427	-0.65531	3.95996	13.766	0	0	0	
+2.428	-0.654554	3.95882	13.7648	0	0	0	
+2.429	-0.653798	3.95767	13.7637	0	0	0	
+2.43	-0.653041	3.9565	13.7625	0	0	0	
+2.431	-0.652283	3.95532	13.7613	0	0	0	
+2.432	-0.651525	3.95412	13.7601	0	0	0	
+2.433	-0.650766	3.9529	13.7589	0	0	0	
+2.434	-0.650006	3.95167	13.7577	0	0	0	
+2.435	-0.649246	3.95042	13.7564	0	0	0	
+2.436	-0.648485	3.94916	13.7552	0	0	0	
+2.437	-0.647724	3.94788	13.7539	0	0	0	
+2.438	-0.646961	3.94658	13.7526	0	0	0	
+2.439	-0.646198	3.94527	13.7513	0	0	0	
+2.44	-0.645435	3.94394	13.7499	0	0	0	
+2.441	-0.644671	3.9426	13.7486	0	0	0	
+2.442	-0.643906	3.94124	13.7472	0	0	0	
+2.443	-0.643141	3.93987	13.7459	0	0	0	
+2.444	-0.642375	3.93848	13.7445	0	0	0	
+2.445	-0.641608	3.93707	13.7431	0	0	0	
+2.446	-0.640841	3.93565	13.7417	0	0	0	
+2.447	-0.640073	3.93422	13.7402	0	0	0	
+2.448	-0.639304	3.93276	13.7388	0	0	0	
+2.449	-0.638535	3.93129	13.7373	0	0	0	
+2.45	-0.637765	3.92981	13.7358	0	0	0	
+2.451	-0.636994	3.92831	13.7343	0	0	0	
+2.452	-0.636223	3.92679	13.7328	0	0	0	
+2.453	-0.635451	3.92526	13.7313	0	0	0	
+2.454	-0.634679	3.92372	13.7297	0	0	0	
+2.455	-0.633906	3.92215	13.7282	0	0	0	
+2.456	-0.633132	3.92058	13.7266	0	0	0	
+2.457	-0.632358	3.91898	13.725	0	0	0	
+2.458	-0.631583	3.91737	13.7234	0	0	0	
+2.459	-0.630807	3.91575	13.7217	0	0	0	
+2.46	-0.630031	3.9141	13.7201	0	0	0	
+2.461	-0.629254	3.91245	13.7184	0	0	0	
+2.462	-0.628476	3.91078	13.7168	0	0	0	
+2.463	-0.627698	3.90909	13.7151	0	0	0	
+2.464	-0.626919	3.90738	13.7134	0	0	0	
+2.465	-0.62614	3.90566	13.7117	0	0	0	
+2.466	-0.62536	3.90393	13.7099	0	0	0	
+2.467	-0.624579	3.90218	13.7082	0	0	0	
+2.468	-0.623798	3.90041	13.7064	0	0	0	
+2.469	-0.623016	3.89863	13.7046	0	0	0	
+2.47	-0.622234	3.89683	13.7028	0	0	0	
+2.471	-0.62145	3.89502	13.701	0	0	0	
+2.472	-0.620667	3.89319	13.6992	0	0	0	
+2.473	-0.619882	3.89135	13.6973	0	0	0	
+2.474	-0.619097	3.88949	13.6955	0	0	0	
+2.475	-0.618312	3.88761	13.6936	0	0	0	
+2.476	-0.617525	3.88572	13.6917	0	0	0	
+2.477	-0.616739	3.88382	13.6898	0	0	0	
+2.478	-0.615951	3.88189	13.6879	0	0	0	
+2.479	-0.615163	3.87996	13.686	0	0	0	
+2.48	-0.614374	3.878	13.684	0	0	0	
+2.481	-0.613585	3.87603	13.682	0	0	0	
+2.482	-0.612795	3.87405	13.6801	0	0	0	
+2.483	-0.612004	3.87205	13.6781	0	0	0	
+2.484	-0.611213	3.87004	13.676	0	0	0	
+2.485	-0.610422	3.86801	13.674	0	0	0	
+2.486	-0.609629	3.86596	13.672	0	0	0	
+2.487	-0.608836	3.8639	13.6699	0	0	0	
+2.488	-0.608043	3.86182	13.6678	0	0	0	
+2.489	-0.607248	3.85973	13.6657	0	0	0	
+2.49	-0.606454	3.85762	13.6636	0	0	0	
+2.491	-0.605658	3.8555	13.6615	0	0	0	
+2.492	-0.604862	3.85336	13.6594	0	0	0	
+2.493	-0.604065	3.85121	13.6572	0	0	0	
+2.494	-0.603268	3.84904	13.655	0	0	0	
+2.495	-0.60247	3.84685	13.6529	0	0	0	
+2.496	-0.601672	3.84465	13.6507	0	0	0	
+2.497	-0.600873	3.84244	13.6484	0	0	0	
+2.498	-0.600073	3.8402	13.6462	0	0	0	
+2.499	-0.599273	3.83796	13.644	0	0	0	
+2.5	-0.598472	3.8357	13.6417	0	0	0	
+2.501	-0.597671	3.83342	13.6394	0	0	0	
+2.502	-0.596869	3.83113	13.6371	0	0	0	
+2.503	-0.596066	3.82882	13.6348	0	0	0	
+2.504	-0.595263	3.8265	13.6325	0	0	0	
+2.505	-0.594459	3.82416	13.6302	0	0	0	
+2.506	-0.593655	3.82181	13.6278	0	0	0	
+2.507	-0.59285	3.81944	13.6254	0	0	0	
+2.508	-0.592044	3.81705	13.6231	0	0	0	
+2.509	-0.591238	3.81465	13.6207	0	0	0	
+2.51	-0.590431	3.81224	13.6182	0	0	0	
+2.511	-0.589624	3.80981	13.6158	0	0	0	
+2.512	-0.588816	3.80736	13.6134	0	0	0	
+2.513	-0.588007	3.8049	13.6109	0	0	0	
+2.514	-0.587198	3.80243	13.6084	0	0	0	
+2.515	-0.586388	3.79994	13.6059	0	0	0	
+2.516	-0.585578	3.79743	13.6034	0	0	0	
+2.517	-0.584767	3.79491	13.6009	0	0	0	
+2.518	-0.583955	3.79237	13.5984	0	0	0	
+2.519	-0.583143	3.78982	13.5958	0	0	0	
+2.52	-0.582331	3.78726	13.5933	0	0	0	
+2.521	-0.581517	3.78467	13.5907	0	0	0	
+2.522	-0.580704	3.78208	13.5881	0	0	0	
+2.523	-0.579889	3.77946	13.5855	0	0	0	
+2.524	-0.579074	3.77684	13.5828	0	0	0	
+2.525	-0.578259	3.77419	13.5802	0	0	0	
+2.526	-0.577442	3.77154	13.5775	0	0	0	
+2.527	-0.576626	3.76886	13.5749	0	0	0	
+2.528	-0.575808	3.76618	13.5722	0	0	0	
+2.529	-0.574991	3.76347	13.5695	0	0	0	
+2.53	-0.574172	3.76076	13.5668	0	0	0	
+2.531	-0.573353	3.75802	13.564	0	0	0	
+2.532	-0.572534	3.75528	13.5613	0	0	0	
+2.533	-0.571713	3.75251	13.5585	0	0	0	
+2.534	-0.570893	3.74974	13.5557	0	0	0	
+2.535	-0.570071	3.74694	13.5529	0	0	0	
+2.536	-0.569249	3.74414	13.5501	0	0	0	
+2.537	-0.568427	3.74131	13.5473	0	0	0	
+2.538	-0.567604	3.73847	13.5445	0	0	0	
+2.539	-0.56678	3.73562	13.5416	0	0	0	
+2.54	-0.565956	3.73275	13.5388	0	0	0	
+2.541	-0.565132	3.72987	13.5359	0	0	0	
+2.542	-0.564306	3.72697	13.533	0	0	0	
+2.543	-0.56348	3.72406	13.5301	0	0	0	
+2.544	-0.562654	3.72113	13.5271	0	0	0	
+2.545	-0.561827	3.71819	13.5242	0	0	0	
+2.546	-0.560999	3.71524	13.5212	0	0	0	
+2.547	-0.560171	3.71226	13.5183	0	0	0	
+2.548	-0.559343	3.70928	13.5153	0	0	0	
+2.549	-0.558513	3.70628	13.5123	0	0	0	
+2.55	-0.557684	3.70326	13.5093	0	0	0	
+2.551	-0.556853	3.70023	13.5062	0	0	0	
+2.552	-0.556022	3.69718	13.5032	0	0	0	
+2.553	-0.555191	3.69412	13.5001	0	0	0	
+2.554	-0.554359	3.69105	13.497	0	0	0	
+2.555	-0.553526	3.68795	13.494	0	0	0	
+2.556	-0.552693	3.68485	13.4908	0	0	0	
+2.557	-0.55186	3.68173	13.4877	0	0	0	
+2.558	-0.551026	3.6786	13.4846	0	0	0	
+2.559	-0.550191	3.67545	13.4814	0	0	0	
+2.56	-0.549355	3.67228	13.4783	0	0	0	
+2.561	-0.54852	3.6691	13.4751	0	0	0	
+2.562	-0.547683	3.66591	13.4719	0	0	0	
+2.563	-0.546846	3.6627	13.4687	0	0	0	
+2.564	-0.546009	3.65948	13.4655	0	0	0	
+2.565	-0.545171	3.65624	13.4622	0	0	0	
+2.566	-0.544332	3.65299	13.459	0	0	0	
+2.567	-0.543493	3.64972	13.4557	0	0	0	
+2.568	-0.542653	3.64644	13.4524	0	0	0	
+2.569	-0.541813	3.64315	13.4491	0	0	0	
+2.57	-0.540972	3.63984	13.4458	0	0	0	
+2.571	-0.540131	3.63651	13.4425	0	0	0	
+2.572	-0.539289	3.63317	13.4392	0	0	0	
+2.573	-0.538447	3.62982	13.4358	0	0	0	
+2.574	-0.537604	3.62645	13.4324	0	0	0	
+2.575	-0.53676	3.62307	13.4291	0	0	0	
+2.576	-0.535916	3.61967	13.4257	0	0	0	
+2.577	-0.535072	3.61626	13.4223	0	0	0	
+2.578	-0.534227	3.61283	13.4188	0	0	0	
+2.579	-0.533381	3.60939	13.4154	0	0	0	
+2.58	-0.532535	3.60593	13.4119	0	0	0	
+2.581	-0.531688	3.60246	13.4085	0	0	0	
+2.582	-0.530841	3.59898	13.405	0	0	0	
+2.583	-0.529993	3.59548	13.4015	0	0	0	
+2.584	-0.529145	3.59197	13.398	0	0	0	
+2.585	-0.528296	3.58844	13.3944	0	0	0	
+2.586	-0.527447	3.5849	13.3909	0	0	0	
+2.587	-0.526597	3.58134	13.3873	0	0	0	
+2.588	-0.525747	3.57777	13.3838	0	0	0	
+2.589	-0.524896	3.57419	13.3802	0	0	0	
+2.59	-0.524044	3.57059	13.3766	0	0	0	
+2.591	-0.523192	3.56698	13.373	0	0	0	
+2.592	-0.52234	3.56335	13.3694	0	0	0	
+2.593	-0.521487	3.55971	13.3657	0	0	0	
+2.594	-0.520633	3.55605	13.3621	0	0	0	
+2.595	-0.519779	3.55238	13.3584	0	0	0	
+2.596	-0.518925	3.5487	13.3547	0	0	0	
+2.597	-0.51807	3.545	13.351	0	0	0	
+2.598	-0.517214	3.54129	13.3473	0	0	0	
+2.599	-0.516358	3.53756	13.3436	0	0	0	
+2.6	-0.515501	3.53382	13.3398	0	0	0	
+2.601	-0.514644	3.53006	13.3361	0	0	0	
+2.602	-0.513787	3.52629	13.3323	0	0	0	
+2.603	-0.512928	3.52251	13.3285	0	0	0	
+2.604	-0.51207	3.51871	13.3247	0	0	0	
+2.605	-0.511211	3.5149	13.3209	0	0	0	
+2.606	-0.510351	3.51108	13.3171	0	0	0	
+2.607	-0.509491	3.50724	13.3132	0	0	0	
+2.608	-0.50863	3.50338	13.3094	0	0	0	
+2.609	-0.507769	3.49951	13.3055	0	0	0	
+2.61	-0.506907	3.49563	13.3016	0	0	0	
+2.611	-0.506045	3.49174	13.2977	0	0	0	
+2.612	-0.505182	3.48783	13.2938	0	0	0	
+2.613	-0.504319	3.4839	13.2899	0	0	0	
+2.614	-0.503455	3.47997	13.286	0	0	0	
+2.615	-0.502591	3.47601	13.282	0	0	0	
+2.616	-0.501726	3.47205	13.278	0	0	0	
+2.617	-0.50086	3.46807	13.2741	0	0	0	
+2.618	-0.499995	3.46408	13.2701	0	0	0	
+2.619	-0.499128	3.46007	13.2661	0	0	0	
+2.62	-0.498262	3.45605	13.262	0	0	0	
+2.621	-0.497394	3.45201	13.258	0	0	0	
+2.622	-0.496527	3.44797	13.254	0	0	0	
+2.623	-0.495658	3.4439	13.2499	0	0	0	
+2.624	-0.49479	3.43983	13.2458	0	0	0	
+2.625	-0.49392	3.43574	13.2417	0	0	0	
+2.626	-0.493051	3.43163	13.2376	0	0	0	
+2.627	-0.49218	3.42752	13.2335	0	0	0	
+2.628	-0.49131	3.42339	13.2294	0	0	0	
+2.629	-0.490438	3.41924	13.2252	0	0	0	
+2.63	-0.489567	3.41508	13.2211	0	0	0	
+2.631	-0.488694	3.41091	13.2169	0	0	0	
+2.632	-0.487822	3.40673	13.2127	0	0	0	
+2.633	-0.486949	3.40253	13.2085	0	0	0	
+2.634	-0.486075	3.39831	13.2043	0	0	0	
+2.635	-0.485201	3.39409	13.2001	0	0	0	
+2.636	-0.484326	3.38985	13.1958	0	0	0	
+2.637	-0.483451	3.38559	13.1916	0	0	0	
+2.638	-0.482575	3.38133	13.1873	0	0	0	
+2.639	-0.481699	3.37705	13.183	0	0	0	
+2.64	-0.480823	3.37275	13.1788	0	0	0	
+2.641	-0.479946	3.36844	13.1744	0	0	0	
+2.642	-0.479068	3.36412	13.1701	0	0	0	
+2.643	-0.47819	3.35979	13.1658	0	0	0	
+2.644	-0.477312	3.35544	13.1614	0	0	0	
+2.645	-0.476433	3.35108	13.1571	0	0	0	
+2.646	-0.475553	3.3467	13.1527	0	0	0	
+2.647	-0.474673	3.34231	13.1483	0	0	0	
+2.648	-0.473793	3.33791	13.1439	0	0	0	
+2.649	-0.472912	3.3335	13.1395	0	0	0	
+2.65	-0.472031	3.32907	13.1351	0	0	0	
+2.651	-0.471149	3.32463	13.1306	0	0	0	
+2.652	-0.470266	3.32017	13.1262	0	0	0	
+2.653	-0.469384	3.3157	13.1217	0	0	0	
+2.654	-0.4685	3.31122	13.1172	0	0	0	
+2.655	-0.467617	3.30673	13.1127	0	0	0	
+2.656	-0.466733	3.30222	13.1082	0	0	0	
+2.657	-0.465848	3.2977	13.1037	0	0	0	
+2.658	-0.464963	3.29317	13.0992	0	0	0	
+2.659	-0.464077	3.28862	13.0946	0	0	0	
+2.66	-0.463191	3.28406	13.0901	0	0	0	
+2.661	-0.462305	3.27948	13.0855	0	0	0	
+2.662	-0.461418	3.2749	13.0809	0	0	0	
+2.663	-0.46053	3.2703	13.0763	0	0	0	
+2.664	-0.459643	3.26568	13.0717	0	0	0	
+2.665	-0.458754	3.26106	13.0671	0	0	0	
+2.666	-0.457865	3.25642	13.0624	0	0	0	
+2.667	-0.456976	3.25177	13.0578	0	0	0	
+2.668	-0.456086	3.2471	13.0531	0	0	0	
+2.669	-0.455196	3.24242	13.0484	0	0	0	
+2.67	-0.454306	3.23773	13.0437	0	0	0	
+2.671	-0.453415	3.23303	13.039	0	0	0	
+2.672	-0.452523	3.22831	13.0343	0	0	0	
+2.673	-0.451631	3.22358	13.0296	0	0	0	
+2.674	-0.450739	3.21884	13.0248	0	0	0	
+2.675	-0.449846	3.21408	13.0201	0	0	0	
+2.676	-0.448952	3.20931	13.0153	0	0	0	
+2.677	-0.448059	3.20453	13.0105	0	0	0	
+2.678	-0.447164	3.19974	13.0057	0	0	0	
+2.679	-0.44627	3.19493	13.0009	0	0	0	
+2.68	-0.445375	3.19011	12.9961	0	0	0	
+2.681	-0.444479	3.18528	12.9913	0	0	0	
+2.682	-0.443583	3.18043	12.9864	0	0	0	
+2.683	-0.442687	3.17557	12.9816	0	0	0	
+2.684	-0.44179	3.1707	12.9767	0	0	0	
+2.685	-0.440892	3.16582	12.9718	0	0	0	
+2.686	-0.439995	3.16092	12.9669	0	0	0	
+2.687	-0.439096	3.15601	12.962	0	0	0	
+2.688	-0.438198	3.15109	12.9571	0	0	0	
+2.689	-0.437299	3.14616	12.9522	0	0	0	
+2.69	-0.436399	3.14121	12.9472	0	0	0	
+2.691	-0.435499	3.13625	12.9423	0	0	0	
+2.692	-0.434599	3.13128	12.9373	0	0	0	
+2.693	-0.433698	3.1263	12.9323	0	0	0	
+2.694	-0.432797	3.1213	12.9273	0	0	0	
+2.695	-0.431895	3.11629	12.9223	0	0	0	
+2.696	-0.430993	3.11127	12.9173	0	0	0	
+2.697	-0.43009	3.10623	12.9122	0	0	0	
+2.698	-0.429187	3.10119	12.9072	0	0	0	
+2.699	-0.428284	3.09613	12.9021	0	0	0	
+2.7	-0.42738	3.09106	12.8971	0	0	0	
+2.701	-0.426476	3.08597	12.892	0	0	0	
+2.702	-0.425571	3.08088	12.8869	0	0	0	
+2.703	-0.424666	3.07577	12.8818	0	0	0	
+2.704	-0.42376	3.07065	12.8766	0	0	0	
+2.705	-0.422854	3.06552	12.8715	0	0	0	
+2.706	-0.421948	3.06037	12.8664	0	0	0	
+2.707	-0.421041	3.05521	12.8612	0	0	0	
+2.708	-0.420134	3.05004	12.856	0	0	0	
+2.709	-0.419226	3.04486	12.8509	0	0	0	
+2.71	-0.418318	3.03967	12.8457	0	0	0	
+2.711	-0.417409	3.03446	12.8405	0	0	0	
+2.712	-0.416501	3.02924	12.8352	0	0	0	
+2.713	-0.415591	3.02401	12.83	0	0	0	
+2.714	-0.414681	3.01877	12.8248	0	0	0	
+2.715	-0.413771	3.01352	12.8195	0	0	0	
+2.716	-0.412861	3.00825	12.8142	0	0	0	
+2.717	-0.41195	3.00297	12.809	0	0	0	
+2.718	-0.411038	2.99768	12.8037	0	0	0	
+2.719	-0.410126	2.99238	12.7984	0	0	0	
+2.72	-0.409214	2.98706	12.7931	0	0	0	
+2.721	-0.408302	2.98173	12.7877	0	0	0	
+2.722	-0.407388	2.9764	12.7824	0	0	0	
+2.723	-0.406475	2.97105	12.777	0	0	0	
+2.724	-0.405561	2.96568	12.7717	0	0	0	
+2.725	-0.404647	2.96031	12.7663	0	0	0	
+2.726	-0.403732	2.95492	12.7609	0	0	0	
+2.727	-0.402817	2.94953	12.7555	0	0	0	
+2.728	-0.401902	2.94412	12.7501	0	0	0	
+2.729	-0.400986	2.93869	12.7447	0	0	0	
+2.73	-0.400069	2.93326	12.7393	0	0	0	
+2.731	-0.399153	2.92782	12.7338	0	0	0	
+2.732	-0.398236	2.92236	12.7284	0	0	0	
+2.733	-0.397318	2.91689	12.7229	0	0	0	
+2.734	-0.3964	2.91141	12.7174	0	0	0	
+2.735	-0.395482	2.90592	12.7119	0	0	0	
+2.736	-0.394563	2.90042	12.7064	0	0	0	
+2.737	-0.393644	2.8949	12.7009	0	0	0	
+2.738	-0.392725	2.88937	12.6954	0	0	0	
+2.739	-0.391805	2.88384	12.6898	0	0	0	
+2.74	-0.390885	2.87829	12.6843	0	0	0	
+2.741	-0.389964	2.87273	12.6787	0	0	0	
+2.742	-0.389043	2.86715	12.6732	0	0	0	
+2.743	-0.388122	2.86157	12.6676	0	0	0	
+2.744	-0.3872	2.85597	12.662	0	0	0	
+2.745	-0.386278	2.85037	12.6564	0	0	0	
+2.746	-0.385355	2.84475	12.6507	0	0	0	
+2.747	-0.384432	2.83912	12.6451	0	0	0	
+2.748	-0.383509	2.83348	12.6395	0	0	0	
+2.749	-0.382585	2.82783	12.6338	0	0	0	
+2.75	-0.381661	2.82216	12.6282	0	0	0	
+2.751	-0.380736	2.81649	12.6225	0	0	0	
+2.752	-0.379812	2.8108	12.6168	0	0	0	
+2.753	-0.378886	2.8051	12.6111	0	0	0	
+2.754	-0.377961	2.79939	12.6054	0	0	0	
+2.755	-0.377035	2.79367	12.5997	0	0	0	
+2.756	-0.376108	2.78794	12.5939	0	0	0	
+2.757	-0.375182	2.7822	12.5882	0	0	0	
+2.758	-0.374254	2.77645	12.5824	0	0	0	
+2.759	-0.373327	2.77068	12.5767	0	0	0	
+2.76	-0.372399	2.76491	12.5709	0	0	0	
+2.761	-0.371471	2.75912	12.5651	0	0	0	
+2.762	-0.370542	2.75332	12.5593	0	0	0	
+2.763	-0.369613	2.74751	12.5535	0	0	0	
+2.764	-0.368684	2.74169	12.5477	0	0	0	
+2.765	-0.367754	2.73586	12.5419	0	0	0	
+2.766	-0.366824	2.73002	12.536	0	0	0	
+2.767	-0.365893	2.72417	12.5302	0	0	0	
+2.768	-0.364963	2.71831	12.5243	0	0	0	
+2.769	-0.364031	2.71243	12.5184	0	0	0	
+2.77	-0.3631	2.70655	12.5125	0	0	0	
+2.771	-0.362168	2.70065	12.5067	0	0	0	
+2.772	-0.361236	2.69474	12.5007	0	0	0	
+2.773	-0.360303	2.68883	12.4948	0	0	0	
+2.774	-0.35937	2.6829	12.4889	0	0	0	
+2.775	-0.358437	2.67696	12.483	0	0	0	
+2.776	-0.357503	2.67101	12.477	0	0	0	
+2.777	-0.356569	2.66505	12.471	0	0	0	
+2.778	-0.355634	2.65908	12.4651	0	0	0	
+2.779	-0.3547	2.6531	12.4591	0	0	0	
+2.78	-0.353764	2.6471	12.4531	0	0	0	
+2.781	-0.352829	2.6411	12.4471	0	0	0	
+2.782	-0.351893	2.63509	12.4411	0	0	0	
+2.783	-0.350957	2.62906	12.4351	0	0	0	
+2.784	-0.35002	2.62303	12.429	0	0	0	
+2.785	-0.349083	2.61698	12.423	0	0	0	
+2.786	-0.348146	2.61093	12.4169	0	0	0	
+2.787	-0.347208	2.60486	12.4109	0	0	0	
+2.788	-0.34627	2.59879	12.4048	0	0	0	
+2.789	-0.345332	2.5927	12.3987	0	0	0	
+2.79	-0.344393	2.5866	12.3926	0	0	0	
+2.791	-0.343454	2.5805	12.3865	0	0	0	
+2.792	-0.342515	2.57438	12.3804	0	0	0	
+2.793	-0.341575	2.56825	12.3742	0	0	0	
+2.794	-0.340635	2.56211	12.3681	0	0	0	
+2.795	-0.339695	2.55596	12.362	0	0	0	
+2.796	-0.338754	2.5498	12.3558	0	0	0	
+2.797	-0.337813	2.54363	12.3496	0	0	0	
+2.798	-0.336872	2.53746	12.3435	0	0	0	
+2.799	-0.33593	2.53127	12.3373	0	0	0	
+2.8	-0.334988	2.52507	12.3311	0	0	0	
+2.801	-0.334046	2.51886	12.3249	0	0	0	
+2.802	-0.333103	2.51264	12.3186	0	0	0	
+2.803	-0.33216	2.50641	12.3124	0	0	0	
+2.804	-0.331217	2.50017	12.3062	0	0	0	
+2.805	-0.330273	2.49392	12.2999	0	0	0	
+2.806	-0.329329	2.48766	12.2937	0	0	0	
+2.807	-0.328384	2.48139	12.2874	0	0	0	
+2.808	-0.32744	2.47511	12.2811	0	0	0	
+2.809	-0.326495	2.46882	12.2748	0	0	0	
+2.81	-0.325549	2.46252	12.2685	0	0	0	
+2.811	-0.324604	2.45621	12.2622	0	0	0	
+2.812	-0.323658	2.44989	12.2559	0	0	0	
+2.813	-0.322711	2.44356	12.2496	0	0	0	
+2.814	-0.321765	2.43722	12.2432	0	0	0	
+2.815	-0.320818	2.43088	12.2369	0	0	0	
+2.816	-0.31987	2.42452	12.2305	0	0	0	
+2.817	-0.318923	2.41815	12.2242	0	0	0	
+2.818	-0.317975	2.41177	12.2178	0	0	0	
+2.819	-0.317027	2.40539	12.2114	0	0	0	
+2.82	-0.316078	2.39899	12.205	0	0	0	
+2.821	-0.315129	2.39258	12.1986	0	0	0	
+2.822	-0.31418	2.38617	12.1922	0	0	0	
+2.823	-0.31323	2.37974	12.1857	0	0	0	
+2.824	-0.312281	2.37331	12.1793	0	0	0	
+2.825	-0.31133	2.36686	12.1729	0	0	0	
+2.826	-0.31038	2.36041	12.1664	0	0	0	
+2.827	-0.309429	2.35395	12.1599	0	0	0	
+2.828	-0.308478	2.34747	12.1535	0	0	0	
+2.829	-0.307527	2.34099	12.147	0	0	0	
+2.83	-0.306575	2.3345	12.1405	0	0	0	
+2.831	-0.305623	2.328	12.134	0	0	0	
+2.832	-0.304671	2.32149	12.1275	0	0	0	
+2.833	-0.303718	2.31497	12.121	0	0	0	
+2.834	-0.302765	2.30844	12.1144	0	0	0	
+2.835	-0.301812	2.3019	12.1079	0	0	0	
+2.836	-0.300858	2.29535	12.1014	0	0	0	
+2.837	-0.299905	2.2888	12.0948	0	0	0	
+2.838	-0.29895	2.28223	12.0882	0	0	0	
+2.839	-0.297996	2.27566	12.0817	0	0	0	
+2.84	-0.297041	2.26907	12.0751	0	0	0	
+2.841	-0.296086	2.26248	12.0685	0	0	0	
+2.842	-0.295131	2.25588	12.0619	0	0	0	
+2.843	-0.294175	2.24927	12.0553	0	0	0	
+2.844	-0.29322	2.24265	12.0486	0	0	0	
+2.845	-0.292263	2.23602	12.042	0	0	0	
+2.846	-0.291307	2.22938	12.0354	0	0	0	
+2.847	-0.29035	2.22274	12.0287	0	0	0	
+2.848	-0.289393	2.21608	12.0221	0	0	0	
+2.849	-0.288436	2.20942	12.0154	0	0	0	
+2.85	-0.287478	2.20274	12.0087	0	0	0	
+2.851	-0.28652	2.19606	12.0021	0	0	0	
+2.852	-0.285562	2.18937	11.9954	0	0	0	
+2.853	-0.284603	2.18267	11.9887	0	0	0	
+2.854	-0.283645	2.17596	11.982	0	0	0	
+2.855	-0.282686	2.16924	11.9752	0	0	0	
+2.856	-0.281726	2.16252	11.9685	0	0	0	
+2.857	-0.280767	2.15578	11.9618	0	0	0	
+2.858	-0.279807	2.14904	11.955	0	0	0	
+2.859	-0.278846	2.14229	11.9483	0	0	0	
+2.86	-0.277886	2.13553	11.9415	0	0	0	
+2.861	-0.276925	2.12876	11.9348	0	0	0	
+2.862	-0.275964	2.12198	11.928	0	0	0	
+2.863	-0.275003	2.1152	11.9212	0	0	0	
+2.864	-0.274041	2.1084	11.9144	0	0	0	
+2.865	-0.273079	2.1016	11.9076	0	0	0	
+2.866	-0.272117	2.09479	11.9008	0	0	0	
+2.867	-0.271155	2.08797	11.894	0	0	0	
+2.868	-0.270192	2.08114	11.8871	0	0	0	
+2.869	-0.269229	2.07431	11.8803	0	0	0	
+2.87	-0.268266	2.06746	11.8735	0	0	0	
+2.871	-0.267303	2.06061	11.8666	0	0	0	
+2.872	-0.266339	2.05375	11.8597	0	0	0	
+2.873	-0.265375	2.04688	11.8529	0	0	0	
+2.874	-0.264411	2.04	11.846	0	0	0	
+2.875	-0.263446	2.03312	11.8391	0	0	0	
+2.876	-0.262481	2.02622	11.8322	0	0	0	
+2.877	-0.261516	2.01932	11.8253	0	0	0	
+2.878	-0.260551	2.01241	11.8184	0	0	0	
+2.879	-0.259585	2.00549	11.8115	0	0	0	
+2.88	-0.258619	1.99857	11.8046	0	0	0	
+2.881	-0.257653	1.99163	11.7976	0	0	0	
+2.882	-0.256687	1.98469	11.7907	0	0	0	
+2.883	-0.25572	1.97774	11.7837	0	0	0	
+2.884	-0.254753	1.97078	11.7768	0	0	0	
+2.885	-0.253786	1.96382	11.7698	0	0	0	
+2.886	-0.252819	1.95685	11.7628	0	0	0	
+2.887	-0.251851	1.94986	11.7559	0	0	0	
+2.888	-0.250883	1.94288	11.7489	0	0	0	
+2.889	-0.249915	1.93588	11.7419	0	0	0	
+2.89	-0.248947	1.92887	11.7349	0	0	0	
+2.891	-0.247978	1.92186	11.7279	0	0	0	
+2.892	-0.247009	1.91484	11.7208	0	0	0	
+2.893	-0.24604	1.90781	11.7138	0	0	0	
+2.894	-0.245071	1.90078	11.7068	0	0	0	
+2.895	-0.244101	1.89374	11.6997	0	0	0	
+2.896	-0.243131	1.88669	11.6927	0	0	0	
+2.897	-0.242161	1.87963	11.6856	0	0	0	
+2.898	-0.241191	1.87256	11.6786	0	0	0	
+2.899	-0.24022	1.86549	11.6715	0	0	0	
+2.9	-0.239249	1.85841	11.6644	0	0	0	
+2.901	-0.238278	1.85132	11.6573	0	0	0	
+2.902	-0.237307	1.84423	11.6502	0	0	0	
+2.903	-0.236335	1.83712	11.6431	0	0	0	
+2.904	-0.235364	1.83001	11.636	0	0	0	
+2.905	-0.234392	1.8229	11.6289	0	0	0	
+2.906	-0.233419	1.81577	11.6218	0	0	0	
+2.907	-0.232447	1.80864	11.6146	0	0	0	
+2.908	-0.231474	1.8015	11.6075	0	0	0	
+2.909	-0.230501	1.79435	11.6004	0	0	0	
+2.91	-0.229528	1.7872	11.5932	0	0	0	
+2.911	-0.228555	1.78004	11.586	0	0	0	
+2.912	-0.227581	1.77287	11.5789	0	0	0	
+2.913	-0.226607	1.7657	11.5717	0	0	0	
+2.914	-0.225633	1.75852	11.5645	0	0	0	
+2.915	-0.224659	1.75133	11.5573	0	0	0	
+2.916	-0.223684	1.74413	11.5501	0	0	0	
+2.917	-0.222709	1.73693	11.5429	0	0	0	
+2.918	-0.221734	1.72972	11.5357	0	0	0	
+2.919	-0.220759	1.7225	11.5285	0	0	0	
+2.92	-0.219784	1.71528	11.5213	0	0	0	
+2.921	-0.218808	1.70805	11.514	0	0	0	
+2.922	-0.217832	1.70081	11.5068	0	0	0	
+2.923	-0.216856	1.69356	11.4996	0	0	0	
+2.924	-0.21588	1.68631	11.4923	0	0	0	
+2.925	-0.214903	1.67906	11.4851	0	0	0	
+2.926	-0.213926	1.67179	11.4778	0	0	0	
+2.927	-0.212949	1.66452	11.4705	0	0	0	
+2.928	-0.211972	1.65724	11.4632	0	0	0	
+2.929	-0.210995	1.64996	11.456	0	0	0	
+2.93	-0.210017	1.64267	11.4487	0	0	0	
+2.931	-0.209039	1.63537	11.4414	0	0	0	
+2.932	-0.208061	1.62807	11.4341	0	0	0	
+2.933	-0.207083	1.62076	11.4268	0	0	0	
+2.934	-0.206105	1.61344	11.4194	0	0	0	
+2.935	-0.205126	1.60611	11.4121	0	0	0	
+2.936	-0.204147	1.59878	11.4048	0	0	0	
+2.937	-0.203168	1.59145	11.3974	0	0	0	
+2.938	-0.202189	1.58411	11.3901	0	0	0	
+2.939	-0.20121	1.57676	11.3828	0	0	0	
+2.94	-0.20023	1.5694	11.3754	0	0	0	
+2.941	-0.19925	1.56204	11.368	0	0	0	
+2.942	-0.19827	1.55467	11.3607	0	0	0	
+2.943	-0.19729	1.5473	11.3533	0	0	0	
+2.944	-0.196309	1.53992	11.3459	0	0	0	
+2.945	-0.195329	1.53253	11.3385	0	0	0	
+2.946	-0.194348	1.52514	11.3311	0	0	0	
+2.947	-0.193367	1.51774	11.3237	0	0	0	
+2.948	-0.192386	1.51033	11.3163	0	0	0	
+2.949	-0.191404	1.50292	11.3089	0	0	0	
+2.95	-0.190423	1.49551	11.3015	0	0	0	
+2.951	-0.189441	1.48808	11.2941	0	0	0	
+2.952	-0.188459	1.48066	11.2867	0	0	0	
+2.953	-0.187477	1.47322	11.2792	0	0	0	
+2.954	-0.186494	1.46578	11.2718	0	0	0	
+2.955	-0.185512	1.45833	11.2643	0	0	0	
+2.956	-0.184529	1.45088	11.2569	0	0	0	
+2.957	-0.183546	1.44342	11.2494	0	0	0	
+2.958	-0.182563	1.43596	11.242	0	0	0	
+2.959	-0.18158	1.42849	11.2345	0	0	0	
+2.96	-0.180596	1.42101	11.227	0	0	0	
+2.961	-0.179613	1.41353	11.2195	0	0	0	
+2.962	-0.178629	1.40605	11.212	0	0	0	
+2.963	-0.177645	1.39855	11.2046	0	0	0	
+2.964	-0.176661	1.39106	11.1971	0	0	0	
+2.965	-0.175676	1.38355	11.1896	0	0	0	
+2.966	-0.174692	1.37604	11.182	0	0	0	
+2.967	-0.173707	1.36853	11.1745	0	0	0	
+2.968	-0.172722	1.36101	11.167	0	0	0	
+2.969	-0.171737	1.35348	11.1595	0	0	0	
+2.97	-0.170752	1.34595	11.152	0	0	0	
+2.971	-0.169766	1.33842	11.1444	0	0	0	
+2.972	-0.168781	1.33088	11.1369	0	0	0	
+2.973	-0.167795	1.32333	11.1293	0	0	0	
+2.974	-0.166809	1.31578	11.1218	0	0	0	
+2.975	-0.165823	1.30822	11.1142	0	0	0	
+2.976	-0.164837	1.30066	11.1067	0	0	0	
+2.977	-0.163851	1.29309	11.0991	0	0	0	
+2.978	-0.162864	1.28552	11.0915	0	0	0	
+2.979	-0.161877	1.27794	11.0839	0	0	0	
+2.98	-0.16089	1.27035	11.0764	0	0	0	
+2.981	-0.159903	1.26277	11.0688	0	0	0	
+2.982	-0.158916	1.25517	11.0612	0	0	0	
+2.983	-0.157929	1.24757	11.0536	0	0	0	
+2.984	-0.156941	1.23997	11.046	0	0	0	
+2.985	-0.155953	1.23236	11.0384	0	0	0	
+2.986	-0.154966	1.22475	11.0307	0	0	0	
+2.987	-0.153978	1.21713	11.0231	0	0	0	
+2.988	-0.152989	1.20951	11.0155	0	0	0	
+2.989	-0.152001	1.20188	11.0079	0	0	0	
+2.99	-0.151013	1.19425	11.0002	0	0	0	
+2.991	-0.150024	1.18661	10.9926	0	0	0	
+2.992	-0.149035	1.17897	10.985	0	0	0	
+2.993	-0.148046	1.17132	10.9773	0	0	0	
+2.994	-0.147057	1.16367	10.9697	0	0	0	
+2.995	-0.146068	1.15601	10.962	0	0	0	
+2.996	-0.145079	1.14835	10.9544	0	0	0	
+2.997	-0.144089	1.14069	10.9467	0	0	0	
+2.998	-0.1431	1.13302	10.939	0	0	0	
+2.999	-0.14211	1.12534	10.9313	0	0	0	
+3	-0.14112	1.11766	10.9237	0	0	0	
+3.001	-0.14013	1.10998	10.916	0	0	0	
+3.002	-0.13914	1.10229	10.9083	0	0	0	
+3.003	-0.138149	1.0946	10.9006	0	0	0	
+3.004	-0.137159	1.0869	10.8929	0	0	0	
+3.005	-0.136168	1.0792	10.8852	0	0	0	
+3.006	-0.135178	1.07149	10.8775	0	0	0	
+3.007	-0.134187	1.06378	10.8698	0	0	0	
+3.008	-0.133196	1.05607	10.8621	0	0	0	
+3.009	-0.132204	1.04835	10.8544	0	0	0	
+3.01	-0.131213	1.04063	10.8466	0	0	0	
+3.011	-0.130222	1.0329	10.8389	0	0	0	
+3.012	-0.12923	1.02517	10.8312	0	0	0	
+3.013	-0.128239	1.01744	10.8234	0	0	0	
+3.014	-0.127247	1.0097	10.8157	0	0	0	
+3.015	-0.126255	1.00196	10.808	0	0	0	
+3.016	-0.125263	0.994209	10.8002	0	0	0	
+3.017	-0.124271	0.986458	10.7925	0	0	0	
+3.018	-0.123278	0.978703	10.7847	0	0	0	
+3.019	-0.122286	0.970944	10.7769	0	0	0	
+3.02	-0.121293	0.963182	10.7692	0	0	0	
+3.021	-0.120301	0.955415	10.7614	0	0	0	
+3.022	-0.119308	0.947645	10.7536	0	0	0	
+3.023	-0.118315	0.939871	10.7459	0	0	0	
+3.024	-0.117322	0.932093	10.7381	0	0	0	
+3.025	-0.116329	0.924311	10.7303	0	0	0	
+3.026	-0.115335	0.916526	10.7225	0	0	0	
+3.027	-0.114342	0.908737	10.7147	0	0	0	
+3.028	-0.113349	0.900944	10.7069	0	0	0	
+3.029	-0.112355	0.893148	10.6991	0	0	0	
+3.03	-0.111361	0.885348	10.6913	0	0	0	
+3.031	-0.110367	0.877545	10.6835	0	0	0	
+3.032	-0.109373	0.869738	10.6757	0	0	0	
+3.033	-0.108379	0.861928	10.6679	0	0	0	
+3.034	-0.107385	0.854114	10.6601	0	0	0	
+3.035	-0.106391	0.846297	10.6523	0	0	0	
+3.036	-0.105397	0.838476	10.6445	0	0	0	
+3.037	-0.104402	0.830652	10.6367	0	0	0	
+3.038	-0.103407	0.822825	10.6288	0	0	0	
+3.039	-0.102413	0.814994	10.621	0	0	0	
+3.04	-0.101418	0.807161	10.6132	0	0	0	
+3.041	-0.100423	0.799323	10.6053	0	0	0	
+3.042	-0.0994281	0.791483	10.5975	0	0	0	
+3.043	-0.098433	0.78364	10.5896	0	0	0	
+3.044	-0.0974378	0.775793	10.5818	0	0	0	
+3.045	-0.0964425	0.767944	10.5739	0	0	0	
+3.046	-0.0954471	0.760091	10.5661	0	0	0	
+3.047	-0.0944517	0.752235	10.5582	0	0	0	
+3.048	-0.0934561	0.744376	10.5504	0	0	0	
+3.049	-0.0924604	0.736515	10.5425	0	0	0	
+3.05	-0.0914646	0.72865	10.5347	0	0	0	
+3.051	-0.0904688	0.720782	10.5268	0	0	0	
+3.052	-0.0894728	0.712912	10.5189	0	0	0	
+3.053	-0.0884768	0.705039	10.511	0	0	0	
+3.054	-0.0874807	0.697162	10.5032	0	0	0	
+3.055	-0.0864845	0.689284	10.4953	0	0	0	
+3.056	-0.0854882	0.681402	10.4874	0	0	0	
+3.057	-0.0844918	0.673517	10.4795	0	0	0	
+3.058	-0.0834953	0.66563	10.4716	0	0	0	
+3.059	-0.0824988	0.65774	10.4637	0	0	0	
+3.06	-0.0815022	0.649848	10.4558	0	0	0	
+3.061	-0.0805054	0.641953	10.448	0	0	0	
+3.062	-0.0795086	0.634055	10.4401	0	0	0	
+3.063	-0.0785118	0.626155	10.4322	0	0	0	
+3.064	-0.0775148	0.618253	10.4243	0	0	0	
+3.065	-0.0765178	0.610348	10.4163	0	0	0	
+3.066	-0.0755207	0.60244	10.4084	0	0	0	
+3.067	-0.0745235	0.59453	10.4005	0	0	0	
+3.068	-0.0735262	0.586618	10.3926	0	0	0	
+3.069	-0.0725289	0.578703	10.3847	0	0	0	
+3.07	-0.0715315	0.570786	10.3768	0	0	0	
+3.071	-0.070534	0.562867	10.3689	0	0	0	
+3.072	-0.0695365	0.554945	10.3609	0	0	0	
+3.073	-0.0685389	0.547022	10.353	0	0	0	
+3.074	-0.0675412	0.539096	10.3451	0	0	0	
+3.075	-0.0665434	0.531168	10.3372	0	0	0	
+3.076	-0.0655456	0.523237	10.3292	0	0	0	
+3.077	-0.0645477	0.515305	10.3213	0	0	0	
+3.078	-0.0635498	0.507371	10.3134	0	0	0	
+3.079	-0.0625518	0.499434	10.3054	0	0	0	
+3.08	-0.0615537	0.491496	10.2975	0	0	0	
+3.081	-0.0605556	0.483556	10.2896	0	0	0	
+3.082	-0.0595574	0.475613	10.2816	0	0	0	
+3.083	-0.0585591	0.467669	10.2737	0	0	0	
+3.084	-0.0575608	0.459723	10.2657	0	0	0	
+3.085	-0.0565624	0.451775	10.2578	0	0	0	
+3.086	-0.055564	0.443825	10.2498	0	0	0	
+3.087	-0.0545655	0.435874	10.2419	0	0	0	
+3.088	-0.053567	0.427921	10.2339	0	0	0	
+3.089	-0.0525684	0.419966	10.226	0	0	0	
+3.09	-0.0515698	0.412009	10.218	0	0	0	
+3.091	-0.0505711	0.404051	10.2101	0	0	0	
+3.092	-0.0495723	0.396091	10.2021	0	0	0	
+3.093	-0.0485735	0.38813	10.1941	0	0	0	
+3.094	-0.0475747	0.380167	10.1862	0	0	0	
+3.095	-0.0465758	0.372202	10.1782	0	0	0	
+3.096	-0.0455769	0.364236	10.1702	0	0	0	
+3.097	-0.0445779	0.356268	10.1623	0	0	0	
+3.098	-0.0435788	0.3483	10.1543	0	0	0	
+3.099	-0.0425798	0.340329	10.1463	0	0	0	
+3.1	-0.0415807	0.332358	10.1384	0	0	0	
+3.101	-0.0405815	0.324385	10.1304	0	0	0	
+3.102	-0.0395823	0.31641	10.1224	0	0	0	
+3.103	-0.0385831	0.308435	10.1144	0	0	0	
+3.104	-0.0375838	0.300458	10.1065	0	0	0	
+3.105	-0.0365845	0.29248	10.0985	0	0	0	
+3.106	-0.0355851	0.284501	10.0905	0	0	0	
+3.107	-0.0345858	0.276521	10.0825	0	0	0	
+3.108	-0.0335863	0.268539	10.0745	0	0	0	
+3.109	-0.0325869	0.260557	10.0666	0	0	0	
+3.11	-0.0315874	0.252573	10.0586	0	0	0	
+3.111	-0.0305879	0.244589	10.0506	0	0	0	
+3.112	-0.0295883	0.236603	10.0426	0	0	0	
+3.113	-0.0285888	0.228617	10.0346	0	0	0	
+3.114	-0.0275892	0.220629	10.0266	0	0	0	
+3.115	-0.0265895	0.212641	10.0186	0	0	0	
+3.116	-0.0255899	0.204652	10.0107	0	0	0	
+3.117	-0.0245902	0.196662	10.0027	0	0	0	
+3.118	-0.0235905	0.188671	9.99467	0	0	0	
+3.119	-0.0225907	0.18068	9.98668	0	0	0	
+3.12	-0.021591	0.172688	9.97869	0	0	0	
+3.121	-0.0205912	0.164695	9.97069	0	0	0	
+3.122	-0.0195914	0.156701	9.9627	0	0	0	
+3.123	-0.0185916	0.148707	9.95471	0	0	0	
+3.124	-0.0175917	0.140712	9.94671	0	0	0	
+3.125	-0.0165919	0.132717	9.93872	0	0	0	
+3.126	-0.015592	0.124721	9.93072	0	0	0	
+3.127	-0.0145921	0.116725	9.92272	0	0	0	
+3.128	-0.0135922	0.108728	9.91473	0	0	0	
+3.129	-0.0125923	0.100731	9.90673	0	0	0	
+3.13	-0.0115924	0.0927329	9.89873	0	0	0	
+3.131	-0.0105925	0.0847349	9.89073	0	0	0	
+3.132	-0.00959251	0.0767365	9.88274	0	0	0	
+3.133	-0.00859255	0.0687378	9.87474	0	0	0	
+3.134	-0.00759258	0.0607389	9.86674	0	0	0	
+3.135	-0.00659261	0.0527397	9.85874	0	0	0	
+3.136	-0.00559262	0.0447403	9.85074	0	0	0	
+3.137	-0.00459264	0.0367407	9.84274	0	0	0	
+3.138	-0.00359265	0.028741	9.83474	0	0	0	
+3.139	-0.00259265	0.0207411	9.82674	0	0	0	
+3.14	-0.00159265	0.0127412	9.81874	0	0	0	
+3.141	-0.000592654	0.00474123	9.81074	0	0	0	
+3.142	0.000407346	-0.00325877	9.80274	0	0	0	
+3.143	0.00140735	-0.0112588	9.79474	0	0	0	
+3.144	0.00240734	-0.0192587	9.78674	0	0	0	
+3.145	0.00340734	-0.0272586	9.77874	0	0	0	
+3.146	0.00440733	-0.0352583	9.77074	0	0	0	
+3.147	0.00540732	-0.0432579	9.76274	0	0	0	
+3.148	0.0064073	-0.0512574	9.75474	0	0	0	
+3.149	0.00740728	-0.0592566	9.74674	0	0	0	
+3.15	0.00840725	-0.0672556	9.73874	0	0	0	
+3.151	0.00940721	-0.0752543	9.73075	0	0	0	
+3.152	0.0104072	-0.0832528	9.72275	0	0	0	
+3.153	0.0114071	-0.0912509	9.71475	0	0	0	
+3.154	0.012407	-0.0992486	9.70675	0	0	0	
+3.155	0.0134069	-0.107246	9.69875	0	0	0	
+3.156	0.0144068	-0.115243	9.69076	0	0	0	
+3.157	0.0154067	-0.123239	9.68276	0	0	0	
+3.158	0.0164066	-0.131235	9.67476	0	0	0	
+3.159	0.0174065	-0.139231	9.66677	0	0	0	
+3.16	0.0184063	-0.147226	9.65877	0	0	0	
+3.161	0.0194061	-0.15522	9.65078	0	0	0	
+3.162	0.0204059	-0.163213	9.64279	0	0	0	
+3.163	0.0214057	-0.171206	9.63479	0	0	0	
+3.164	0.0224055	-0.179199	9.6268	0	0	0	
+3.165	0.0234052	-0.18719	9.61881	0	0	0	
+3.166	0.0244049	-0.195181	9.61082	0	0	0	
+3.167	0.0254046	-0.203171	9.60283	0	0	0	
+3.168	0.0264043	-0.211161	9.59484	0	0	0	
+3.169	0.0274039	-0.219149	9.58685	0	0	0	
+3.17	0.0284035	-0.227137	9.57886	0	0	0	
+3.171	0.0294031	-0.235123	9.57088	0	0	0	
+3.172	0.0304027	-0.243109	9.56289	0	0	0	
+3.173	0.0314022	-0.251094	9.55491	0	0	0	
+3.174	0.0324017	-0.259077	9.54692	0	0	0	
+3.175	0.0334011	-0.26706	9.53894	0	0	0	
+3.176	0.0344006	-0.275042	9.53096	0	0	0	
+3.177	0.0353999	-0.283022	9.52298	0	0	0	
+3.178	0.0363993	-0.291001	9.515	0	0	0	
+3.179	0.0373986	-0.29898	9.50702	0	0	0	
+3.18	0.0383979	-0.306957	9.49904	0	0	0	
+3.181	0.0393971	-0.314932	9.49107	0	0	0	
+3.182	0.0403964	-0.322907	9.48309	0	0	0	
+3.183	0.0413955	-0.33088	9.47512	0	0	0	
+3.184	0.0423946	-0.338852	9.46715	0	0	0	
+3.185	0.0433937	-0.346823	9.45918	0	0	0	
+3.186	0.0443928	-0.354792	9.45121	0	0	0	
+3.187	0.0453917	-0.36276	9.44324	0	0	0	
+3.188	0.0463907	-0.370726	9.43527	0	0	0	
+3.189	0.0473896	-0.378691	9.42731	0	0	0	
+3.19	0.0483884	-0.386654	9.41935	0	0	0	
+3.191	0.0493872	-0.394616	9.41138	0	0	0	
+3.192	0.050386	-0.402576	9.40342	0	0	0	
+3.193	0.0513847	-0.410535	9.39547	0	0	0	
+3.194	0.0523834	-0.418492	9.38751	0	0	0	
+3.195	0.053382	-0.426447	9.37955	0	0	0	
+3.196	0.0543805	-0.4344	9.3716	0	0	0	
+3.197	0.055379	-0.442352	9.36365	0	0	0	
+3.198	0.0563774	-0.450302	9.3557	0	0	0	
+3.199	0.0573758	-0.45825	9.34775	0	0	0	
+3.2	0.0583741	-0.466197	9.3398	0	0	0	
+3.201	0.0593724	-0.474141	9.33186	0	0	0	
+3.202	0.0603706	-0.482084	9.32392	0	0	0	
+3.203	0.0613688	-0.490025	9.31598	0	0	0	
+3.204	0.0623668	-0.497963	9.30804	0	0	0	
+3.205	0.0633649	-0.5059	9.3001	0	0	0	
+3.206	0.0643628	-0.513835	9.29217	0	0	0	
+3.207	0.0653607	-0.521768	9.28423	0	0	0	
+3.208	0.0663585	-0.529698	9.2763	0	0	0	
+3.209	0.0673563	-0.537627	9.26837	0	0	0	
+3.21	0.068354	-0.545553	9.26045	0	0	0	
+3.211	0.0693516	-0.553477	9.25252	0	0	0	
+3.212	0.0703492	-0.561399	9.2446	0	0	0	
+3.213	0.0713467	-0.569319	9.23668	0	0	0	
+3.214	0.0723441	-0.577236	9.22876	0	0	0	
+3.215	0.0733414	-0.585151	9.22085	0	0	0	
+3.216	0.0743387	-0.593064	9.21294	0	0	0	
+3.217	0.0753359	-0.600975	9.20503	0	0	0	
+3.218	0.076333	-0.608882	9.19712	0	0	0	
+3.219	0.0773301	-0.616788	9.18921	0	0	0	
+3.22	0.078327	-0.624691	9.18131	0	0	0	
+3.221	0.0793239	-0.632592	9.17341	0	0	0	
+3.222	0.0803207	-0.64049	9.16551	0	0	0	
+3.223	0.0813175	-0.648385	9.15761	0	0	0	
+3.224	0.0823141	-0.656278	9.14972	0	0	0	
+3.225	0.0833107	-0.664168	9.14183	0	0	0	
+3.226	0.0843072	-0.672056	9.13394	0	0	0	
+3.227	0.0853036	-0.679941	9.12606	0	0	0	
+3.228	0.0862999	-0.687823	9.11818	0	0	0	
+3.229	0.0872961	-0.695703	9.1103	0	0	0	
+3.23	0.0882922	-0.703579	9.10242	0	0	0	
+3.231	0.0892883	-0.711453	9.09455	0	0	0	
+3.232	0.0902842	-0.719324	9.08668	0	0	0	
+3.233	0.0912801	-0.727192	9.07881	0	0	0	
+3.234	0.0922759	-0.735058	9.07094	0	0	0	
+3.235	0.0932716	-0.74292	9.06308	0	0	0	
+3.236	0.0942672	-0.750779	9.05522	0	0	0	
+3.237	0.0952627	-0.758635	9.04736	0	0	0	
+3.238	0.0962581	-0.766489	9.03951	0	0	0	
+3.239	0.0972534	-0.774339	9.03166	0	0	0	
+3.24	0.0982486	-0.782186	9.02381	0	0	0	
+3.241	0.0992437	-0.79003	9.01597	0	0	0	
+3.242	0.100239	-0.797871	9.00813	0	0	0	
+3.243	0.101234	-0.805709	9.00029	0	0	0	
+3.244	0.102228	-0.813543	8.99246	0	0	0	
+3.245	0.103223	-0.821374	8.98463	0	0	0	
+3.246	0.104218	-0.829202	8.9768	0	0	0	
+3.247	0.105212	-0.837027	8.96897	0	0	0	
+3.248	0.106207	-0.844848	8.96115	0	0	0	
+3.249	0.107201	-0.852666	8.95333	0	0	0	
+3.25	0.108195	-0.86048	8.94552	0	0	0	
+3.251	0.109189	-0.868291	8.93771	0	0	0	
+3.252	0.110183	-0.876098	8.9299	0	0	0	
+3.253	0.111177	-0.883902	8.9221	0	0	0	
+3.254	0.112171	-0.891703	8.9143	0	0	0	
+3.255	0.113164	-0.8995	8.9065	0	0	0	
+3.256	0.114158	-0.907293	8.89871	0	0	0	
+3.257	0.115151	-0.915083	8.89092	0	0	0	
+3.258	0.116145	-0.922869	8.88313	0	0	0	
+3.259	0.117138	-0.930651	8.87535	0	0	0	
+3.26	0.118131	-0.93843	8.86757	0	0	0	
+3.261	0.119124	-0.946205	8.8598	0	0	0	
+3.262	0.120117	-0.953976	8.85202	0	0	0	
+3.263	0.121109	-0.961743	8.84426	0	0	0	
+3.264	0.122102	-0.969506	8.83649	0	0	0	
+3.265	0.123094	-0.977266	8.82873	0	0	0	
+3.266	0.124087	-0.985021	8.82098	0	0	0	
+3.267	0.125079	-0.992773	8.81323	0	0	0	
+3.268	0.126071	-1.00052	8.80548	0	0	0	
+3.269	0.127063	-1.00826	8.79774	0	0	0	
+3.27	0.128055	-1.016	8.79	0	0	0	
+3.271	0.129046	-1.02374	8.78226	0	0	0	
+3.272	0.130038	-1.03147	8.77453	0	0	0	
+3.273	0.131029	-1.0392	8.7668	0	0	0	
+3.274	0.132021	-1.04692	8.75908	0	0	0	
+3.275	0.133012	-1.05464	8.75136	0	0	0	
+3.276	0.134003	-1.06236	8.74364	0	0	0	
+3.277	0.134994	-1.07007	8.73593	0	0	0	
+3.278	0.135985	-1.07777	8.72823	0	0	0	
+3.279	0.136975	-1.08547	8.72053	0	0	0	
+3.28	0.137966	-1.09317	8.71283	0	0	0	
+3.281	0.138956	-1.10087	8.70513	0	0	0	
+3.282	0.139946	-1.10855	8.69745	0	0	0	
+3.283	0.140937	-1.11624	8.68976	0	0	0	
+3.284	0.141927	-1.12392	8.68208	0	0	0	
+3.285	0.142916	-1.13159	8.67441	0	0	0	
+3.286	0.143906	-1.13926	8.66674	0	0	0	
+3.287	0.144895	-1.14693	8.65907	0	0	0	
+3.288	0.145885	-1.15459	8.65141	0	0	0	
+3.289	0.146874	-1.16225	8.64375	0	0	0	
+3.29	0.147863	-1.1699	8.6361	0	0	0	
+3.291	0.148852	-1.17755	8.62845	0	0	0	
+3.292	0.149841	-1.18519	8.62081	0	0	0	
+3.293	0.15083	-1.19283	8.61317	0	0	0	
+3.294	0.151818	-1.20047	8.60553	0	0	0	
+3.295	0.152806	-1.20809	8.59791	0	0	0	
+3.296	0.153795	-1.21572	8.59028	0	0	0	
+3.297	0.154783	-1.22334	8.58266	0	0	0	
+3.298	0.15577	-1.23095	8.57505	0	0	0	
+3.299	0.156758	-1.23856	8.56744	0	0	0	
+3.3	0.157746	-1.24617	8.55983	0	0	0	
+3.301	0.158733	-1.25376	8.55224	0	0	0	
+3.302	0.15972	-1.26136	8.54464	0	0	0	
+3.303	0.160707	-1.26895	8.53705	0	0	0	
+3.304	0.161694	-1.27653	8.52947	0	0	0	
+3.305	0.162681	-1.28411	8.52189	0	0	0	
+3.306	0.163668	-1.29169	8.51431	0	0	0	
+3.307	0.164654	-1.29925	8.50675	0	0	0	
+3.308	0.16564	-1.30682	8.49918	0	0	0	
+3.309	0.166627	-1.31438	8.49162	0	0	0	
+3.31	0.167612	-1.32193	8.48407	0	0	0	
+3.311	0.168598	-1.32948	8.47652	0	0	0	
+3.312	0.169584	-1.33702	8.46898	0	0	0	
+3.313	0.170569	-1.34456	8.46144	0	0	0	
+3.314	0.171555	-1.35209	8.45391	0	0	0	
+3.315	0.17254	-1.35962	8.44638	0	0	0	
+3.316	0.173525	-1.36714	8.43886	0	0	0	
+3.317	0.174509	-1.37465	8.43135	0	0	0	
+3.318	0.175494	-1.38216	8.42384	0	0	0	
+3.319	0.176478	-1.38967	8.41633	0	0	0	
+3.32	0.177462	-1.39717	8.40883	0	0	0	
+3.321	0.178446	-1.40466	8.40134	0	0	0	
+3.322	0.17943	-1.41215	8.39385	0	0	0	
+3.323	0.180414	-1.41963	8.38637	0	0	0	
+3.324	0.181398	-1.4271	8.3789	0	0	0	
+3.325	0.182381	-1.43458	8.37142	0	0	0	
+3.326	0.183364	-1.44204	8.36396	0	0	0	
+3.327	0.184347	-1.4495	8.3565	0	0	0	
+3.328	0.18533	-1.45695	8.34905	0	0	0	
+3.329	0.186312	-1.4644	8.3416	0	0	0	
+3.33	0.187295	-1.47184	8.33416	0	0	0	
+3.331	0.188277	-1.47928	8.32672	0	0	0	
+3.332	0.189259	-1.48671	8.31929	0	0	0	
+3.333	0.190241	-1.49413	8.31187	0	0	0	
+3.334	0.191222	-1.50155	8.30445	0	0	0	
+3.335	0.192204	-1.50896	8.29704	0	0	0	
+3.336	0.193185	-1.51637	8.28963	0	0	0	
+3.337	0.194166	-1.52377	8.28223	0	0	0	
+3.338	0.195147	-1.53116	8.27484	0	0	0	
+3.339	0.196128	-1.53855	8.26745	0	0	0	
+3.34	0.197108	-1.54593	8.26007	0	0	0	
+3.341	0.198088	-1.55331	8.25269	0	0	0	
+3.342	0.199069	-1.56067	8.24533	0	0	0	
+3.343	0.200048	-1.56804	8.23796	0	0	0	
+3.344	0.201028	-1.57539	8.23061	0	0	0	
+3.345	0.202008	-1.58274	8.22326	0	0	0	
+3.346	0.202987	-1.59009	8.21591	0	0	0	
+3.347	0.203966	-1.59743	8.20857	0	0	0	
+3.348	0.204945	-1.60476	8.20124	0	0	0	
+3.349	0.205924	-1.61208	8.19392	0	0	0	
+3.35	0.206902	-1.6194	8.1866	0	0	0	
+3.351	0.20788	-1.62671	8.17929	0	0	0	
+3.352	0.208858	-1.63402	8.17198	0	0	0	
+3.353	0.209836	-1.64132	8.16468	0	0	0	
+3.354	0.210814	-1.64861	8.15739	0	0	0	
+3.355	0.211791	-1.65589	8.15011	0	0	0	
+3.356	0.212768	-1.66317	8.14283	0	0	0	
+3.357	0.213745	-1.67044	8.13556	0	0	0	
+3.358	0.214722	-1.67771	8.12829	0	0	0	
+3.359	0.215699	-1.68497	8.12103	0	0	0	
+3.36	0.216675	-1.69222	8.11378	0	0	0	
+3.361	0.217651	-1.69947	8.10653	0	0	0	
+3.362	0.218627	-1.70671	8.09929	0	0	0	
+3.363	0.219603	-1.71394	8.09206	0	0	0	
+3.364	0.220578	-1.72116	8.08484	0	0	0	
+3.365	0.221554	-1.72838	8.07762	0	0	0	
+3.366	0.222529	-1.73559	8.07041	0	0	0	
+3.367	0.223503	-1.7428	8.0632	0	0	0	
+3.368	0.224478	-1.74999	8.05601	0	0	0	
+3.369	0.225452	-1.75718	8.04882	0	0	0	
+3.37	0.226427	-1.76437	8.04163	0	0	0	
+3.371	0.2274	-1.77154	8.03446	0	0	0	
+3.372	0.228374	-1.77871	8.02729	0	0	0	
+3.373	0.229348	-1.78587	8.02013	0	0	0	
+3.374	0.230321	-1.79303	8.01297	0	0	0	
+3.375	0.231294	-1.80018	8.00582	0	0	0	
+3.376	0.232267	-1.80732	7.99868	0	0	0	
+3.377	0.233239	-1.81445	7.99155	0	0	0	
+3.378	0.234211	-1.82158	7.98442	0	0	0	
+3.379	0.235183	-1.82869	7.97731	0	0	0	
+3.38	0.236155	-1.83581	7.97019	0	0	0	
+3.381	0.237127	-1.84291	7.96309	0	0	0	
+3.382	0.238098	-1.85001	7.95599	0	0	0	
+3.383	0.239069	-1.8571	7.9489	0	0	0	
+3.384	0.24004	-1.86418	7.94182	0	0	0	
+3.385	0.241011	-1.87125	7.93475	0	0	0	
+3.386	0.241981	-1.87832	7.92768	0	0	0	
+3.387	0.242951	-1.88538	7.92062	0	0	0	
+3.388	0.243921	-1.89243	7.91357	0	0	0	
+3.389	0.244891	-1.89947	7.90653	0	0	0	
+3.39	0.245861	-1.90651	7.89949	0	0	0	
+3.391	0.24683	-1.91354	7.89246	0	0	0	
+3.392	0.247799	-1.92056	7.88544	0	0	0	
+3.393	0.248767	-1.92758	7.87842	0	0	0	
+3.394	0.249736	-1.93458	7.87142	0	0	0	
+3.395	0.250704	-1.94158	7.86442	0	0	0	
+3.396	0.251672	-1.94857	7.85743	0	0	0	
+3.397	0.25264	-1.95555	7.85045	0	0	0	
+3.398	0.253607	-1.96253	7.84347	0	0	0	
+3.399	0.254574	-1.96949	7.83651	0	0	0	
+3.4	0.255541	-1.97645	7.82955	0	0	0	
+3.401	0.256508	-1.9834	7.8226	0	0	0	
+3.402	0.257474	-1.99035	7.81565	0	0	0	
+3.403	0.25844	-1.99728	7.80872	0	0	0	
+3.404	0.259406	-2.00421	7.80179	0	0	0	
+3.405	0.260372	-2.01113	7.79487	0	0	0	
+3.406	0.261337	-2.01804	7.78796	0	0	0	
+3.407	0.262302	-2.02494	7.78106	0	0	0	
+3.408	0.263267	-2.03184	7.77416	0	0	0	
+3.409	0.264232	-2.03873	7.76727	0	0	0	
+3.41	0.265196	-2.04561	7.76039	0	0	0	
+3.411	0.26616	-2.05248	7.75352	0	0	0	
+3.412	0.267124	-2.05934	7.74666	0	0	0	
+3.413	0.268088	-2.06619	7.73981	0	0	0	
+3.414	0.269051	-2.07304	7.73296	0	0	0	
+3.415	0.270014	-2.07988	7.72612	0	0	0	
+3.416	0.270977	-2.08671	7.71929	0	0	0	
+3.417	0.271939	-2.09353	7.71247	0	0	0	
+3.418	0.272901	-2.10034	7.70566	0	0	0	
+3.419	0.273863	-2.10714	7.69886	0	0	0	
+3.42	0.274825	-2.11394	7.69206	0	0	0	
+3.421	0.275786	-2.12073	7.68527	0	0	0	
+3.422	0.276747	-2.12751	7.67849	0	0	0	
+3.423	0.277708	-2.13428	7.67172	0	0	0	
+3.424	0.278668	-2.14104	7.66496	0	0	0	
+3.425	0.279629	-2.14779	7.65821	0	0	0	
+3.426	0.280589	-2.15454	7.65146	0	0	0	
+3.427	0.281548	-2.16127	7.64473	0	0	0	
+3.428	0.282508	-2.168	7.638	0	0	0	
+3.429	0.283467	-2.17472	7.63128	0	0	0	
+3.43	0.284426	-2.18143	7.62457	0	0	0	
+3.431	0.285384	-2.18813	7.61787	0	0	0	
+3.432	0.286343	-2.19482	7.61118	0	0	0	
+3.433	0.287301	-2.2015	7.6045	0	0	0	
+3.434	0.288258	-2.20818	7.59782	0	0	0	
+3.435	0.289216	-2.21485	7.59115	0	0	0	
+3.436	0.290173	-2.2215	7.5845	0	0	0	
+3.437	0.29113	-2.22815	7.57785	0	0	0	
+3.438	0.292086	-2.23479	7.57121	0	0	0	
+3.439	0.293042	-2.24142	7.56458	0	0	0	
+3.44	0.293998	-2.24804	7.55796	0	0	0	
+3.441	0.294954	-2.25466	7.55134	0	0	0	
+3.442	0.295909	-2.26126	7.54474	0	0	0	
+3.443	0.296864	-2.26785	7.53815	0	0	0	
+3.444	0.297819	-2.27444	7.53156	0	0	0	
+3.445	0.298774	-2.28101	7.52499	0	0	0	
+3.446	0.299728	-2.28758	7.51842	0	0	0	
+3.447	0.300682	-2.29414	7.51186	0	0	0	
+3.448	0.301635	-2.30069	7.50531	0	0	0	
+3.449	0.302589	-2.30723	7.49877	0	0	0	
+3.45	0.303542	-2.31376	7.49224	0	0	0	
+3.451	0.304494	-2.32028	7.48572	0	0	0	
+3.452	0.305447	-2.32679	7.47921	0	0	0	
+3.453	0.306399	-2.33329	7.47271	0	0	0	
+3.454	0.30735	-2.33979	7.46621	0	0	0	
+3.455	0.308302	-2.34627	7.45973	0	0	0	
+3.456	0.309253	-2.35275	7.45325	0	0	0	
+3.457	0.310204	-2.35921	7.44679	0	0	0	
+3.458	0.311154	-2.36567	7.44033	0	0	0	
+3.459	0.312104	-2.37211	7.43389	0	0	0	
+3.46	0.313054	-2.37855	7.42745	0	0	0	
+3.461	0.314004	-2.38498	7.42102	0	0	0	
+3.462	0.314953	-2.39139	7.41461	0	0	0	
+3.463	0.315902	-2.3978	7.4082	0	0	0	
+3.464	0.316851	-2.4042	7.4018	0	0	0	
+3.465	0.317799	-2.41059	7.39541	0	0	0	
+3.466	0.318747	-2.41697	7.38903	0	0	0	
+3.467	0.319695	-2.42334	7.38266	0	0	0	
+3.468	0.320642	-2.4297	7.3763	0	0	0	
+3.469	0.321589	-2.43605	7.36995	0	0	0	
+3.47	0.322536	-2.44239	7.36361	0	0	0	
+3.471	0.323482	-2.44872	7.35728	0	0	0	
+3.472	0.324428	-2.45504	7.35096	0	0	0	
+3.473	0.325374	-2.46135	7.34465	0	0	0	
+3.474	0.32632	-2.46765	7.33835	0	0	0	
+3.475	0.327265	-2.47394	7.33206	0	0	0	
+3.476	0.328209	-2.48023	7.32577	0	0	0	
+3.477	0.329154	-2.4865	7.3195	0	0	0	
+3.478	0.330098	-2.49276	7.31324	0	0	0	
+3.479	0.331042	-2.49901	7.30699	0	0	0	
+3.48	0.331985	-2.50525	7.30075	0	0	0	
+3.481	0.332928	-2.51148	7.29452	0	0	0	
+3.482	0.333871	-2.51771	7.28829	0	0	0	
+3.483	0.334814	-2.52392	7.28208	0	0	0	
+3.484	0.335756	-2.53012	7.27588	0	0	0	
+3.485	0.336697	-2.53631	7.26969	0	0	0	
+3.486	0.337639	-2.54249	7.26351	0	0	0	
+3.487	0.33858	-2.54866	7.25734	0	0	0	
+3.488	0.339521	-2.55482	7.25118	0	0	0	
+3.489	0.340461	-2.56097	7.24503	0	0	0	
+3.49	0.341401	-2.56711	7.23889	0	0	0	
+3.491	0.342341	-2.57324	7.23276	0	0	0	
+3.492	0.34328	-2.57936	7.22664	0	0	0	
+3.493	0.344219	-2.58547	7.22053	0	0	0	
+3.494	0.345158	-2.59157	7.21443	0	0	0	
+3.495	0.346097	-2.59766	7.20834	0	0	0	
+3.496	0.347035	-2.60374	7.20226	0	0	0	
+3.497	0.347972	-2.60981	7.19619	0	0	0	
+3.498	0.34891	-2.61586	7.19014	0	0	0	
+3.499	0.349847	-2.62191	7.18409	0	0	0	
+3.5	0.350783	-2.62795	7.17805	0	0	0	
+3.501	0.35172	-2.63397	7.17203	0	0	0	
+3.502	0.352655	-2.63999	7.16601	0	0	0	
+3.503	0.353591	-2.64599	7.16001	0	0	0	
+3.504	0.354526	-2.65199	7.15401	0	0	0	
+3.505	0.355461	-2.65797	7.14803	0	0	0	
+3.506	0.356396	-2.66394	7.14206	0	0	0	
+3.507	0.35733	-2.66991	7.13609	0	0	0	
+3.508	0.358264	-2.67586	7.13014	0	0	0	
+3.509	0.359197	-2.6818	7.1242	0	0	0	
+3.51	0.36013	-2.68773	7.11827	0	0	0	
+3.511	0.361063	-2.69365	7.11235	0	0	0	
+3.512	0.361995	-2.69956	7.10644	0	0	0	
+3.513	0.362927	-2.70546	7.10054	0	0	0	
+3.514	0.363859	-2.71134	7.09466	0	0	0	
+3.515	0.36479	-2.71722	7.08878	0	0	0	
+3.516	0.365721	-2.72308	7.08292	0	0	0	
+3.517	0.366652	-2.72894	7.07706	0	0	0	
+3.518	0.367582	-2.73478	7.07122	0	0	0	
+3.519	0.368512	-2.74061	7.06539	0	0	0	
+3.52	0.369441	-2.74644	7.05956	0	0	0	
+3.521	0.37037	-2.75225	7.05375	0	0	0	
+3.522	0.371299	-2.75805	7.04795	0	0	0	
+3.523	0.372227	-2.76384	7.04216	0	0	0	
+3.524	0.373155	-2.76961	7.03639	0	0	0	
+3.525	0.374083	-2.77538	7.03062	0	0	0	
+3.526	0.37501	-2.78114	7.02486	0	0	0	
+3.527	0.375937	-2.78688	7.01912	0	0	0	
+3.528	0.376863	-2.79261	7.01339	0	0	0	
+3.529	0.377789	-2.79833	7.00767	0	0	0	
+3.53	0.378715	-2.80405	7.00195	0	0	0	
+3.531	0.37964	-2.80975	6.99625	0	0	0	
+3.532	0.380565	-2.81543	6.99057	0	0	0	
+3.533	0.38149	-2.82111	6.98489	0	0	0	
+3.534	0.382414	-2.82678	6.97922	0	0	0	
+3.535	0.383338	-2.83243	6.97357	0	0	0	
+3.536	0.384261	-2.83807	6.96793	0	0	0	
+3.537	0.385184	-2.84371	6.96229	0	0	0	
+3.538	0.386107	-2.84933	6.95667	0	0	0	
+3.539	0.387029	-2.85494	6.95106	0	0	0	
+3.54	0.387951	-2.86053	6.94547	0	0	0	
+3.541	0.388872	-2.86612	6.93988	0	0	0	
+3.542	0.389794	-2.87169	6.93431	0	0	0	
+3.543	0.390714	-2.87726	6.92874	0	0	0	
+3.544	0.391635	-2.88281	6.92319	0	0	0	
+3.545	0.392554	-2.88835	6.91765	0	0	0	
+3.546	0.393474	-2.89388	6.91212	0	0	0	
+3.547	0.394393	-2.89939	6.90661	0	0	0	
+3.548	0.395312	-2.9049	6.9011	0	0	0	
+3.549	0.39623	-2.91039	6.89561	0	0	0	
+3.55	0.397148	-2.91588	6.89012	0	0	0	
+3.551	0.398066	-2.92135	6.88465	0	0	0	
+3.552	0.398983	-2.92681	6.87919	0	0	0	
+3.553	0.3999	-2.93225	6.87375	0	0	0	
+3.554	0.400816	-2.93769	6.86831	0	0	0	
+3.555	0.401732	-2.94311	6.86289	0	0	0	
+3.556	0.402648	-2.94852	6.85748	0	0	0	
+3.557	0.403563	-2.95392	6.85208	0	0	0	
+3.558	0.404477	-2.95931	6.84669	0	0	0	
+3.559	0.405392	-2.96469	6.84131	0	0	0	
+3.56	0.406306	-2.97005	6.83595	0	0	0	
+3.561	0.407219	-2.97541	6.83059	0	0	0	
+3.562	0.408132	-2.98075	6.82525	0	0	0	
+3.563	0.409045	-2.98608	6.81992	0	0	0	
+3.564	0.409957	-2.99139	6.81461	0	0	0	
+3.565	0.410869	-2.9967	6.8093	0	0	0	
+3.566	0.411781	-3.00199	6.80401	0	0	0	
+3.567	0.412692	-3.00727	6.79873	0	0	0	
+3.568	0.413603	-3.01254	6.79346	0	0	0	
+3.569	0.414513	-3.0178	6.7882	0	0	0	
+3.57	0.415423	-3.02304	6.78296	0	0	0	
+3.571	0.416332	-3.02827	6.77773	0	0	0	
+3.572	0.417241	-3.0335	6.7725	0	0	0	
+3.573	0.41815	-3.0387	6.7673	0	0	0	
+3.574	0.419058	-3.0439	6.7621	0	0	0	
+3.575	0.419966	-3.04908	6.75692	0	0	0	
+3.576	0.420873	-3.05426	6.75174	0	0	0	
+3.577	0.42178	-3.05942	6.74658	0	0	0	
+3.578	0.422686	-3.06456	6.74144	0	0	0	
+3.579	0.423592	-3.0697	6.7363	0	0	0	
+3.58	0.424498	-3.07482	6.73118	0	0	0	
+3.581	0.425403	-3.07993	6.72607	0	0	0	
+3.582	0.426308	-3.08503	6.72097	0	0	0	
+3.583	0.427212	-3.09012	6.71588	0	0	0	
+3.584	0.428116	-3.09519	6.71081	0	0	0	
+3.585	0.42902	-3.10025	6.70575	0	0	0	
+3.586	0.429923	-3.1053	6.7007	0	0	0	
+3.587	0.430826	-3.11034	6.69566	0	0	0	
+3.588	0.431728	-3.11536	6.69064	0	0	0	
+3.589	0.43263	-3.12037	6.68563	0	0	0	
+3.59	0.433531	-3.12537	6.68063	0	0	0	
+3.591	0.434432	-3.13036	6.67564	0	0	0	
+3.592	0.435332	-3.13533	6.67067	0	0	0	
+3.593	0.436232	-3.14029	6.66571	0	0	0	
+3.594	0.437132	-3.14524	6.66076	0	0	0	
+3.595	0.438031	-3.15018	6.65582	0	0	0	
+3.596	0.43893	-3.1551	6.6509	0	0	0	
+3.597	0.439828	-3.16001	6.64599	0	0	0	
+3.598	0.440726	-3.16491	6.64109	0	0	0	
+3.599	0.441623	-3.1698	6.6362	0	0	0	
+3.6	0.44252	-3.17467	6.63133	0	0	0	
+3.601	0.443417	-3.17953	6.62647	0	0	0	
+3.602	0.444313	-3.18438	6.62162	0	0	0	
+3.603	0.445209	-3.18921	6.61679	0	0	0	
+3.604	0.446104	-3.19404	6.61196	0	0	0	
+3.605	0.446999	-3.19885	6.60715	0	0	0	
+3.606	0.447893	-3.20364	6.60236	0	0	0	
+3.607	0.448787	-3.20843	6.59757	0	0	0	
+3.608	0.44968	-3.2132	6.5928	0	0	0	
+3.609	0.450573	-3.21796	6.58804	0	0	0	
+3.61	0.451466	-3.2227	6.5833	0	0	0	
+3.611	0.452358	-3.22743	6.57857	0	0	0	
+3.612	0.453249	-3.23215	6.57385	0	0	0	
+3.613	0.454141	-3.23686	6.56914	0	0	0	
+3.614	0.455031	-3.24155	6.56445	0	0	0	
+3.615	0.455922	-3.24623	6.55977	0	0	0	
+3.616	0.456811	-3.2509	6.5551	0	0	0	
+3.617	0.457701	-3.25556	6.55044	0	0	0	
+3.618	0.45859	-3.2602	6.5458	0	0	0	
+3.619	0.459478	-3.26483	6.54117	0	0	0	
+3.62	0.460366	-3.26944	6.53656	0	0	0	
+3.621	0.461253	-3.27404	6.53196	0	0	0	
+3.622	0.46214	-3.27863	6.52737	0	0	0	
+3.623	0.463027	-3.28321	6.52279	0	0	0	
+3.624	0.463913	-3.28777	6.51823	0	0	0	
+3.625	0.464799	-3.29232	6.51368	0	0	0	
+3.626	0.465684	-3.29686	6.50914	0	0	0	
+3.627	0.466569	-3.30138	6.50462	0	0	0	
+3.628	0.467453	-3.30589	6.50011	0	0	0	
+3.629	0.468337	-3.31039	6.49561	0	0	0	
+3.63	0.46922	-3.31488	6.49112	0	0	0	
+3.631	0.470103	-3.31935	6.48665	0	0	0	
+3.632	0.470985	-3.3238	6.4822	0	0	0	
+3.633	0.471867	-3.32825	6.47775	0	0	0	
+3.634	0.472749	-3.33268	6.47332	0	0	0	
+3.635	0.47363	-3.3371	6.4689	0	0	0	
+3.636	0.47451	-3.3415	6.4645	0	0	0	
+3.637	0.47539	-3.34589	6.46011	0	0	0	
+3.638	0.47627	-3.35027	6.45573	0	0	0	
+3.639	0.477149	-3.35463	6.45137	0	0	0	
+3.64	0.478027	-3.35898	6.44702	0	0	0	
+3.641	0.478905	-3.36332	6.44268	0	0	0	
+3.642	0.479783	-3.36764	6.43836	0	0	0	
+3.643	0.48066	-3.37195	6.43405	0	0	0	
+3.644	0.481537	-3.37625	6.42975	0	0	0	
+3.645	0.482413	-3.38053	6.42547	0	0	0	
+3.646	0.483289	-3.3848	6.4212	0	0	0	
+3.647	0.484164	-3.38906	6.41694	0	0	0	
+3.648	0.485039	-3.3933	6.4127	0	0	0	
+3.649	0.485913	-3.39753	6.40847	0	0	0	
+3.65	0.486787	-3.40175	6.40425	0	0	0	
+3.651	0.48766	-3.40595	6.40005	0	0	0	
+3.652	0.488533	-3.41014	6.39586	0	0	0	
+3.653	0.489405	-3.41431	6.39169	0	0	0	
+3.654	0.490277	-3.41847	6.38753	0	0	0	
+3.655	0.491148	-3.42262	6.38338	0	0	0	
+3.656	0.492019	-3.42675	6.37925	0	0	0	
+3.657	0.492889	-3.43087	6.37513	0	0	0	
+3.658	0.493759	-3.43498	6.37102	0	0	0	
+3.659	0.494629	-3.43907	6.36693	0	0	0	
+3.66	0.495497	-3.44315	6.36285	0	0	0	
+3.661	0.496366	-3.44721	6.35879	0	0	0	
+3.662	0.497234	-3.45127	6.35473	0	0	0	
+3.663	0.498101	-3.4553	6.3507	0	0	0	
+3.664	0.498968	-3.45933	6.34667	0	0	0	
+3.665	0.499834	-3.46334	6.34266	0	0	0	
+3.666	0.5007	-3.46733	6.33867	0	0	0	
+3.667	0.501565	-3.47131	6.33469	0	0	0	
+3.668	0.50243	-3.47528	6.33072	0	0	0	
+3.669	0.503295	-3.47924	6.32676	0	0	0	
+3.67	0.504159	-3.48318	6.32282	0	0	0	
+3.671	0.505022	-3.4871	6.3189	0	0	0	
+3.672	0.505885	-3.49101	6.31499	0	0	0	
+3.673	0.506747	-3.49491	6.31109	0	0	0	
+3.674	0.507609	-3.4988	6.3072	0	0	0	
+3.675	0.50847	-3.50267	6.30333	0	0	0	
+3.676	0.509331	-3.50652	6.29948	0	0	0	
+3.677	0.510191	-3.51037	6.29563	0	0	0	
+3.678	0.511051	-3.51419	6.29181	0	0	0	
+3.679	0.511911	-3.51801	6.28799	0	0	0	
+3.68	0.512769	-3.52181	6.28419	0	0	0	
+3.681	0.513628	-3.52559	6.28041	0	0	0	
+3.682	0.514485	-3.52937	6.27663	0	0	0	
+3.683	0.515343	-3.53312	6.27288	0	0	0	
+3.684	0.516199	-3.53687	6.26913	0	0	0	
+3.685	0.517056	-3.5406	6.2654	0	0	0	
+3.686	0.517911	-3.54431	6.26169	0	0	0	
+3.687	0.518766	-3.54801	6.25799	0	0	0	
+3.688	0.519621	-3.5517	6.2543	0	0	0	
+3.689	0.520475	-3.55537	6.25063	0	0	0	
+3.69	0.521329	-3.55903	6.24697	0	0	0	
+3.691	0.522182	-3.56268	6.24332	0	0	0	
+3.692	0.523034	-3.56631	6.23969	0	0	0	
+3.693	0.523887	-3.56992	6.23608	0	0	0	
+3.694	0.524738	-3.57352	6.23248	0	0	0	
+3.695	0.525589	-3.57711	6.22889	0	0	0	
+3.696	0.52644	-3.58068	6.22532	0	0	0	
+3.697	0.527289	-3.58424	6.22176	0	0	0	
+3.698	0.528139	-3.58779	6.21821	0	0	0	
+3.699	0.528988	-3.59132	6.21468	0	0	0	
+3.7	0.529836	-3.59483	6.21117	0	0	0	
+3.701	0.530684	-3.59833	6.20767	0	0	0	
+3.702	0.531531	-3.60182	6.20418	0	0	0	
+3.703	0.532378	-3.60529	6.20071	0	0	0	
+3.704	0.533224	-3.60875	6.19725	0	0	0	
+3.705	0.53407	-3.61219	6.19381	0	0	0	
+3.706	0.534915	-3.61562	6.19038	0	0	0	
+3.707	0.53576	-3.61904	6.18696	0	0	0	
+3.708	0.536604	-3.62244	6.18356	0	0	0	
+3.709	0.537447	-3.62582	6.18018	0	0	0	
+3.71	0.538291	-3.62919	6.17681	0	0	0	
+3.711	0.539133	-3.63255	6.17345	0	0	0	
+3.712	0.539975	-3.63589	6.17011	0	0	0	
+3.713	0.540816	-3.63922	6.16678	0	0	0	
+3.714	0.541657	-3.64253	6.16347	0	0	0	
+3.715	0.542498	-3.64583	6.16017	0	0	0	
+3.716	0.543337	-3.64912	6.15688	0	0	0	
+3.717	0.544177	-3.65239	6.15361	0	0	0	
+3.718	0.545015	-3.65564	6.15036	0	0	0	
+3.719	0.545853	-3.65888	6.14712	0	0	0	
+3.72	0.546691	-3.66211	6.14389	0	0	0	
+3.721	0.547528	-3.66532	6.14068	0	0	0	
+3.722	0.548365	-3.66851	6.13749	0	0	0	
+3.723	0.549201	-3.67169	6.13431	0	0	0	
+3.724	0.550036	-3.67486	6.13114	0	0	0	
+3.725	0.550871	-3.67801	6.12799	0	0	0	
+3.726	0.551705	-3.68115	6.12485	0	0	0	
+3.727	0.552539	-3.68427	6.12173	0	0	0	
+3.728	0.553372	-3.68738	6.11862	0	0	0	
+3.729	0.554205	-3.69047	6.11553	0	0	0	
+3.73	0.555037	-3.69355	6.11245	0	0	0	
+3.731	0.555868	-3.69662	6.10938	0	0	0	
+3.732	0.556699	-3.69966	6.10634	0	0	0	
+3.733	0.55753	-3.7027	6.1033	0	0	0	
+3.734	0.55836	-3.70572	6.10028	0	0	0	
+3.735	0.559189	-3.70872	6.09728	0	0	0	
+3.736	0.560018	-3.71171	6.09429	0	0	0	
+3.737	0.560846	-3.71469	6.09131	0	0	0	
+3.738	0.561674	-3.71765	6.08835	0	0	0	
+3.739	0.562501	-3.72059	6.08541	0	0	0	
+3.74	0.563327	-3.72352	6.08248	0	0	0	
+3.741	0.564153	-3.72644	6.07956	0	0	0	
+3.742	0.564979	-3.72934	6.07666	0	0	0	
+3.743	0.565803	-3.73222	6.07378	0	0	0	
+3.744	0.566628	-3.73509	6.07091	0	0	0	
+3.745	0.567451	-3.73795	6.06805	0	0	0	
+3.746	0.568275	-3.74079	6.06521	0	0	0	
+3.747	0.569097	-3.74361	6.06239	0	0	0	
+3.748	0.569919	-3.74642	6.05958	0	0	0	
+3.749	0.57074	-3.74922	6.05678	0	0	0	
+3.75	0.571561	-3.752	6.054	0	0	0	
+3.751	0.572382	-3.75477	6.05123	0	0	0	
+3.752	0.573201	-3.75752	6.04848	0	0	0	
+3.753	0.57402	-3.76025	6.04575	0	0	0	
+3.754	0.574839	-3.76297	6.04303	0	0	0	
+3.755	0.575657	-3.76568	6.04032	0	0	0	
+3.756	0.576474	-3.76837	6.03763	0	0	0	
+3.757	0.577291	-3.77104	6.03496	0	0	0	
+3.758	0.578107	-3.7737	6.0323	0	0	0	
+3.759	0.578923	-3.77635	6.02965	0	0	0	
+3.76	0.579738	-3.77898	6.02702	0	0	0	
+3.761	0.580553	-3.78159	6.02441	0	0	0	
+3.762	0.581367	-3.78419	6.02181	0	0	0	
+3.763	0.58218	-3.78678	6.01922	0	0	0	
+3.764	0.582993	-3.78935	6.01665	0	0	0	
+3.765	0.583805	-3.7919	6.0141	0	0	0	
+3.766	0.584617	-3.79444	6.01156	0	0	0	
+3.767	0.585428	-3.79696	6.00904	0	0	0	
+3.768	0.586238	-3.79947	6.00653	0	0	0	
+3.769	0.587048	-3.80197	6.00403	0	0	0	
+3.77	0.587857	-3.80445	6.00155	0	0	0	
+3.771	0.588666	-3.80691	5.99909	0	0	0	
+3.772	0.589474	-3.80936	5.99664	0	0	0	
+3.773	0.590281	-3.81179	5.99421	0	0	0	
+3.774	0.591088	-3.81421	5.99179	0	0	0	
+3.775	0.591895	-3.81661	5.98939	0	0	0	
+3.776	0.5927	-3.819	5.987	0	0	0	
+3.777	0.593505	-3.82137	5.98463	0	0	0	
+3.778	0.59431	-3.82372	5.98228	0	0	0	
+3.779	0.595114	-3.82607	5.97993	0	0	0	
+3.78	0.595917	-3.82839	5.97761	0	0	0	
+3.781	0.59672	-3.8307	5.9753	0	0	0	
+3.782	0.597522	-3.833	5.973	0	0	0	
+3.783	0.598324	-3.83528	5.97072	0	0	0	
+3.784	0.599125	-3.83754	5.96846	0	0	0	
+3.785	0.599925	-3.83979	5.96621	0	0	0	
+3.786	0.600725	-3.84202	5.96398	0	0	0	
+3.787	0.601524	-3.84424	5.96176	0	0	0	
+3.788	0.602322	-3.84645	5.95955	0	0	0	
+3.789	0.60312	-3.84863	5.95737	0	0	0	
+3.79	0.603918	-3.8508	5.9552	0	0	0	
+3.791	0.604714	-3.85296	5.95304	0	0	0	
+3.792	0.605511	-3.8551	5.9509	0	0	0	
+3.793	0.606306	-3.85723	5.94877	0	0	0	
+3.794	0.607101	-3.85934	5.94666	0	0	0	
+3.795	0.607895	-3.86143	5.94457	0	0	0	
+3.796	0.608689	-3.86351	5.94249	0	0	0	
+3.797	0.609482	-3.86558	5.94042	0	0	0	
+3.798	0.610275	-3.86763	5.93837	0	0	0	
+3.799	0.611067	-3.86966	5.93634	0	0	0	
+3.8	0.611858	-3.87168	5.93432	0	0	0	
+3.801	0.612649	-3.87368	5.93232	0	0	0	
+3.802	0.613439	-3.87567	5.93033	0	0	0	
+3.803	0.614228	-3.87764	5.92836	0	0	0	
+3.804	0.615017	-3.8796	5.9264	0	0	0	
+3.805	0.615805	-3.88154	5.92446	0	0	0	
+3.806	0.616593	-3.88346	5.92254	0	0	0	
+3.807	0.61738	-3.88537	5.92063	0	0	0	
+3.808	0.618166	-3.88726	5.91874	0	0	0	
+3.809	0.618952	-3.88914	5.91686	0	0	0	
+3.81	0.619737	-3.891	5.915	0	0	0	
+3.811	0.620521	-3.89285	5.91315	0	0	0	
+3.812	0.621305	-3.89468	5.91132	0	0	0	
+3.813	0.622088	-3.8965	5.9095	0	0	0	
+3.814	0.622871	-3.8983	5.9077	0	0	0	
+3.815	0.623653	-3.90008	5.90592	0	0	0	
+3.816	0.624435	-3.90185	5.90415	0	0	0	
+3.817	0.625215	-3.90361	5.90239	0	0	0	
+3.818	0.625995	-3.90534	5.90066	0	0	0	
+3.819	0.626775	-3.90707	5.89893	0	0	0	
+3.82	0.627554	-3.90877	5.89723	0	0	0	
+3.821	0.628332	-3.91046	5.89554	0	0	0	
+3.822	0.62911	-3.91214	5.89386	0	0	0	
+3.823	0.629887	-3.9138	5.8922	0	0	0	
+3.824	0.630663	-3.91544	5.89056	0	0	0	
+3.825	0.631439	-3.91707	5.88893	0	0	0	
+3.826	0.632214	-3.91868	5.88732	0	0	0	
+3.827	0.632988	-3.92028	5.88572	0	0	0	
+3.828	0.633762	-3.92186	5.88414	0	0	0	
+3.829	0.634535	-3.92343	5.88257	0	0	0	
+3.83	0.635308	-3.92498	5.88102	0	0	0	
+3.831	0.63608	-3.92651	5.87949	0	0	0	
+3.832	0.636851	-3.92803	5.87797	0	0	0	
+3.833	0.637622	-3.92953	5.87647	0	0	0	
+3.834	0.638392	-3.93102	5.87498	0	0	0	
+3.835	0.639161	-3.93249	5.87351	0	0	0	
+3.836	0.63993	-3.93395	5.87205	0	0	0	
+3.837	0.640698	-3.93539	5.87061	0	0	0	
+3.838	0.641466	-3.93681	5.86919	0	0	0	
+3.839	0.642233	-3.93822	5.86778	0	0	0	
+3.84	0.642999	-3.93961	5.86639	0	0	0	
+3.841	0.643764	-3.94099	5.86501	0	0	0	
+3.842	0.644529	-3.94235	5.86365	0	0	0	
+3.843	0.645293	-3.9437	5.8623	0	0	0	
+3.844	0.646057	-3.94503	5.86097	0	0	0	
+3.845	0.64682	-3.94634	5.85966	0	0	0	
+3.846	0.647582	-3.94764	5.85836	0	0	0	
+3.847	0.648344	-3.94892	5.85708	0	0	0	
+3.848	0.649105	-3.95019	5.85581	0	0	0	
+3.849	0.649865	-3.95144	5.85456	0	0	0	
+3.85	0.650625	-3.95267	5.85333	0	0	0	
+3.851	0.651384	-3.95389	5.85211	0	0	0	
+3.852	0.652143	-3.9551	5.8509	0	0	0	
+3.853	0.6529	-3.95628	5.84972	0	0	0	
+3.854	0.653658	-3.95745	5.84855	0	0	0	
+3.855	0.654414	-3.95861	5.84739	0	0	0	
+3.856	0.65517	-3.95975	5.84625	0	0	0	
+3.857	0.655925	-3.96087	5.84513	0	0	0	
+3.858	0.656679	-3.96198	5.84402	0	0	0	
+3.859	0.657433	-3.96307	5.84293	0	0	0	
+3.86	0.658186	-3.96415	5.84185	0	0	0	
+3.861	0.658939	-3.96521	5.84079	0	0	0	
+3.862	0.659691	-3.96626	5.83974	0	0	0	
+3.863	0.660442	-3.96729	5.83871	0	0	0	
+3.864	0.661193	-3.9683	5.8377	0	0	0	
+3.865	0.661943	-3.9693	5.8367	0	0	0	
+3.866	0.662692	-3.97028	5.83572	0	0	0	
+3.867	0.66344	-3.97124	5.83476	0	0	0	
+3.868	0.664188	-3.97219	5.83381	0	0	0	
+3.869	0.664935	-3.97313	5.83287	0	0	0	
+3.87	0.665682	-3.97404	5.83196	0	0	0	
+3.871	0.666428	-3.97495	5.83105	0	0	0	
+3.872	0.667173	-3.97583	5.83017	0	0	0	
+3.873	0.667918	-3.9767	5.8293	0	0	0	
+3.874	0.668662	-3.97756	5.82844	0	0	0	
+3.875	0.669405	-3.9784	5.8276	0	0	0	
+3.876	0.670147	-3.97922	5.82678	0	0	0	
+3.877	0.670889	-3.98002	5.82598	0	0	0	
+3.878	0.671631	-3.98081	5.82519	0	0	0	
+3.879	0.672371	-3.98159	5.82441	0	0	0	
+3.88	0.673111	-3.98235	5.82365	0	0	0	
+3.881	0.67385	-3.98309	5.82291	0	0	0	
+3.882	0.674589	-3.98382	5.82218	0	0	0	
+3.883	0.675327	-3.98453	5.82147	0	0	0	
+3.884	0.676064	-3.98522	5.82078	0	0	0	
+3.885	0.6768	-3.9859	5.8201	0	0	0	
+3.886	0.677536	-3.98657	5.81943	0	0	0	
+3.887	0.678271	-3.98721	5.81879	0	0	0	
+3.888	0.679006	-3.98784	5.81816	0	0	0	
+3.889	0.679739	-3.98846	5.81754	0	0	0	
+3.89	0.680473	-3.98906	5.81694	0	0	0	
+3.891	0.681205	-3.98964	5.81636	0	0	0	
+3.892	0.681937	-3.99021	5.81579	0	0	0	
+3.893	0.682668	-3.99076	5.81524	0	0	0	
+3.894	0.683398	-3.9913	5.8147	0	0	0	
+3.895	0.684128	-3.99182	5.81418	0	0	0	
+3.896	0.684857	-3.99232	5.81368	0	0	0	
+3.897	0.685585	-3.99281	5.81319	0	0	0	
+3.898	0.686313	-3.99328	5.81272	0	0	0	
+3.899	0.68704	-3.99373	5.81227	0	0	0	
+3.9	0.687766	-3.99417	5.81183	0	0	0	
+3.901	0.688492	-3.9946	5.8114	0	0	0	
+3.902	0.689217	-3.995	5.811	0	0	0	
+3.903	0.689941	-3.9954	5.8106	0	0	0	
+3.904	0.690664	-3.99577	5.81023	0	0	0	
+3.905	0.691387	-3.99613	5.80987	0	0	0	
+3.906	0.692109	-3.99648	5.80952	0	0	0	
+3.907	0.692831	-3.9968	5.8092	0	0	0	
+3.908	0.693552	-3.99712	5.80888	0	0	0	
+3.909	0.694272	-3.99741	5.80859	0	0	0	
+3.91	0.694991	-3.99769	5.80831	0	0	0	
+3.911	0.69571	-3.99795	5.80805	0	0	0	
+3.912	0.696428	-3.9982	5.8078	0	0	0	
+3.913	0.697145	-3.99843	5.80757	0	0	0	
+3.914	0.697861	-3.99865	5.80735	0	0	0	
+3.915	0.698577	-3.99885	5.80715	0	0	0	
+3.916	0.699293	-3.99903	5.80697	0	0	0	
+3.917	0.700007	-3.9992	5.8068	0	0	0	
+3.918	0.700721	-3.99935	5.80665	0	0	0	
+3.919	0.701434	-3.99949	5.80651	0	0	0	
+3.92	0.702146	-3.99961	5.80639	0	0	0	
+3.921	0.702858	-3.99971	5.80629	0	0	0	
+3.922	0.703569	-3.9998	5.8062	0	0	0	
+3.923	0.704279	-3.99987	5.80613	0	0	0	
+3.924	0.704989	-3.99993	5.80607	0	0	0	
+3.925	0.705698	-3.99997	5.80603	0	0	0	
+3.926	0.706406	-3.99999	5.80601	0	0	0	
+3.927	0.707113	-4	5.806	0	0	0	
+3.928	0.70782	-3.99999	5.80601	0	0	0	
+3.929	0.708526	-3.99997	5.80603	0	0	0	
+3.93	0.709231	-3.99993	5.80607	0	0	0	
+3.931	0.709936	-3.99987	5.80613	0	0	0	
+3.932	0.71064	-3.9998	5.8062	0	0	0	
+3.933	0.711343	-3.99971	5.80629	0	0	0	
+3.934	0.712046	-3.99961	5.80639	0	0	0	
+3.935	0.712747	-3.99949	5.80651	0	0	0	
+3.936	0.713448	-3.99935	5.80665	0	0	0	
+3.937	0.714149	-3.9992	5.8068	0	0	0	
+3.938	0.714848	-3.99903	5.80697	0	0	0	
+3.939	0.715547	-3.99885	5.80715	0	0	0	
+3.94	0.716246	-3.99865	5.80735	0	0	0	
+3.941	0.716943	-3.99843	5.80757	0	0	0	
+3.942	0.71764	-3.9982	5.8078	0	0	0	
+3.943	0.718336	-3.99795	5.80805	0	0	0	
+3.944	0.719031	-3.99769	5.80831	0	0	0	
+3.945	0.719726	-3.99741	5.80859	0	0	0	
+3.946	0.72042	-3.99711	5.80889	0	0	0	
+3.947	0.721113	-3.9968	5.8092	0	0	0	
+3.948	0.721805	-3.99647	5.80953	0	0	0	
+3.949	0.722497	-3.99613	5.80987	0	0	0	
+3.95	0.723188	-3.99577	5.81023	0	0	0	
+3.951	0.723878	-3.99539	5.81061	0	0	0	
+3.952	0.724568	-3.995	5.811	0	0	0	
+3.953	0.725257	-3.99459	5.81141	0	0	0	
+3.954	0.725945	-3.99417	5.81183	0	0	0	
+3.955	0.726632	-3.99373	5.81227	0	0	0	
+3.956	0.727319	-3.99327	5.81273	0	0	0	
+3.957	0.728005	-3.9928	5.8132	0	0	0	
+3.958	0.72869	-3.99231	5.81369	0	0	0	
+3.959	0.729375	-3.99181	5.81419	0	0	0	
+3.96	0.730058	-3.99129	5.81471	0	0	0	
+3.961	0.730741	-3.99075	5.81525	0	0	0	
+3.962	0.731424	-3.9902	5.8158	0	0	0	
+3.963	0.732105	-3.98963	5.81637	0	0	0	
+3.964	0.732786	-3.98905	5.81695	0	0	0	
+3.965	0.733466	-3.98845	5.81755	0	0	0	
+3.966	0.734146	-3.98783	5.81817	0	0	0	
+3.967	0.734824	-3.9872	5.8188	0	0	0	
+3.968	0.735502	-3.98655	5.81945	0	0	0	
+3.969	0.736179	-3.98589	5.82011	0	0	0	
+3.97	0.736856	-3.98521	5.82079	0	0	0	
+3.971	0.737531	-3.98452	5.82148	0	0	0	
+3.972	0.738206	-3.9838	5.8222	0	0	0	
+3.973	0.73888	-3.98308	5.82292	0	0	0	
+3.974	0.739554	-3.98233	5.82367	0	0	0	
+3.975	0.740227	-3.98158	5.82442	0	0	0	
+3.976	0.740899	-3.9808	5.8252	0	0	0	
+3.977	0.74157	-3.98001	5.82599	0	0	0	
+3.978	0.74224	-3.9792	5.8268	0	0	0	
+3.979	0.74291	-3.97838	5.82762	0	0	0	
+3.98	0.743579	-3.97754	5.82846	0	0	0	
+3.981	0.744247	-3.97669	5.82931	0	0	0	
+3.982	0.744915	-3.97582	5.83018	0	0	0	
+3.983	0.745582	-3.97493	5.83107	0	0	0	
+3.984	0.746248	-3.97403	5.83197	0	0	0	
+3.985	0.746913	-3.97311	5.83289	0	0	0	
+3.986	0.747578	-3.97218	5.83382	0	0	0	
+3.987	0.748241	-3.97123	5.83477	0	0	0	
+3.988	0.748904	-3.97026	5.83574	0	0	0	
+3.989	0.749567	-3.96928	5.83672	0	0	0	
+3.99	0.750228	-3.96828	5.83772	0	0	0	
+3.991	0.750889	-3.96727	5.83873	0	0	0	
+3.992	0.751549	-3.96624	5.83976	0	0	0	
+3.993	0.752208	-3.96519	5.84081	0	0	0	
+3.994	0.752867	-3.96413	5.84187	0	0	0	
+3.995	0.753525	-3.96306	5.84294	0	0	0	
+3.996	0.754182	-3.96196	5.84404	0	0	0	
+3.997	0.754838	-3.96085	5.84515	0	0	0	
+3.998	0.755494	-3.95973	5.84627	0	0	0	
+3.999	0.756148	-3.95859	5.84741	0	0	0	
+4	0.756802	-3.95743	5.84857	0	0	0	
+4.001	0.757456	-3.95626	5.84974	0	0	0	
+4.002	0.758108	-3.95507	5.85093	0	0	0	
+4.003	0.75876	-3.95387	5.85213	0	0	0	
+4.004	0.759411	-3.95265	5.85335	0	0	0	
+4.005	0.760061	-3.95142	5.85458	0	0	0	
+4.006	0.760711	-3.95016	5.85584	0	0	0	
+4.007	0.761359	-3.9489	5.8571	0	0	0	
+4.008	0.762007	-3.94761	5.85839	0	0	0	
+4.009	0.762655	-3.94632	5.85968	0	0	0	
+4.01	0.763301	-3.945	5.861	0	0	0	
+4.011	0.763947	-3.94367	5.86233	0	0	0	
+4.012	0.764592	-3.94233	5.86367	0	0	0	
+4.013	0.765236	-3.94097	5.86503	0	0	0	
+4.014	0.765879	-3.93959	5.86641	0	0	0	
+4.015	0.766522	-3.93819	5.86781	0	0	0	
+4.016	0.767163	-3.93679	5.86921	0	0	0	
+4.017	0.767805	-3.93536	5.87064	0	0	0	
+4.018	0.768445	-3.93392	5.87208	0	0	0	
+4.019	0.769084	-3.93247	5.87353	0	0	0	
+4.02	0.769723	-3.93099	5.87501	0	0	0	
+4.021	0.770361	-3.92951	5.87649	0	0	0	
+4.022	0.770998	-3.928	5.878	0	0	0	
+4.023	0.771635	-3.92648	5.87952	0	0	0	
+4.024	0.77227	-3.92495	5.88105	0	0	0	
+4.025	0.772905	-3.9234	5.8826	0	0	0	
+4.026	0.77354	-3.92183	5.88417	0	0	0	
+4.027	0.774173	-3.92025	5.88575	0	0	0	
+4.028	0.774805	-3.91865	5.88735	0	0	0	
+4.029	0.775437	-3.91704	5.88896	0	0	0	
+4.03	0.776068	-3.91541	5.89059	0	0	0	
+4.031	0.776699	-3.91377	5.89223	0	0	0	
+4.032	0.777328	-3.91211	5.89389	0	0	0	
+4.033	0.777957	-3.91043	5.89557	0	0	0	
+4.034	0.778585	-3.90874	5.89726	0	0	0	
+4.035	0.779212	-3.90703	5.89897	0	0	0	
+4.036	0.779838	-3.90531	5.90069	0	0	0	
+4.037	0.780464	-3.90357	5.90243	0	0	0	
+4.038	0.781089	-3.90182	5.90418	0	0	0	
+4.039	0.781713	-3.90005	5.90595	0	0	0	
+4.04	0.782336	-3.89827	5.90773	0	0	0	
+4.041	0.782958	-3.89647	5.90953	0	0	0	
+4.042	0.78358	-3.89465	5.91135	0	0	0	
+4.043	0.784201	-3.89282	5.91318	0	0	0	
+4.044	0.784821	-3.89097	5.91503	0	0	0	
+4.045	0.78544	-3.88911	5.91689	0	0	0	
+4.046	0.786059	-3.88723	5.91877	0	0	0	
+4.047	0.786677	-3.88533	5.92067	0	0	0	
+4.048	0.787294	-3.88342	5.92258	0	0	0	
+4.049	0.78791	-3.8815	5.9245	0	0	0	
+4.05	0.788525	-3.87956	5.92644	0	0	0	
+4.051	0.78914	-3.8776	5.9284	0	0	0	
+4.052	0.789754	-3.87563	5.93037	0	0	0	
+4.053	0.790367	-3.87364	5.93236	0	0	0	
+4.054	0.790979	-3.87164	5.93436	0	0	0	
+4.055	0.79159	-3.86962	5.93638	0	0	0	
+4.056	0.792201	-3.86759	5.93841	0	0	0	
+4.057	0.792811	-3.86554	5.94046	0	0	0	
+4.058	0.79342	-3.86348	5.94252	0	0	0	
+4.059	0.794028	-3.8614	5.9446	0	0	0	
+4.06	0.794636	-3.8593	5.9467	0	0	0	
+4.061	0.795242	-3.85719	5.94881	0	0	0	
+4.062	0.795848	-3.85506	5.95094	0	0	0	
+4.063	0.796453	-3.85292	5.95308	0	0	0	
+4.064	0.797058	-3.85077	5.95523	0	0	0	
+4.065	0.797661	-3.84859	5.95741	0	0	0	
+4.066	0.798264	-3.8464	5.9596	0	0	0	
+4.067	0.798866	-3.8442	5.9618	0	0	0	
+4.068	0.799467	-3.84198	5.96402	0	0	0	
+4.069	0.800067	-3.83975	5.96625	0	0	0	
+4.07	0.800667	-3.8375	5.9685	0	0	0	
+4.071	0.801265	-3.83523	5.97077	0	0	0	
+4.072	0.801863	-3.83295	5.97305	0	0	0	
+4.073	0.802461	-3.83066	5.97534	0	0	0	
+4.074	0.803057	-3.82835	5.97765	0	0	0	
+4.075	0.803652	-3.82602	5.97998	0	0	0	
+4.076	0.804247	-3.82368	5.98232	0	0	0	
+4.077	0.804841	-3.82132	5.98468	0	0	0	
+4.078	0.805434	-3.81895	5.98705	0	0	0	
+4.079	0.806026	-3.81657	5.98943	0	0	0	
+4.08	0.806618	-3.81416	5.99184	0	0	0	
+4.081	0.807208	-3.81174	5.99426	0	0	0	
+4.082	0.807798	-3.80931	5.99669	0	0	0	
+4.083	0.808387	-3.80686	5.99914	0	0	0	
+4.084	0.808976	-3.8044	6.0016	0	0	0	
+4.085	0.809563	-3.80192	6.00408	0	0	0	
+4.086	0.81015	-3.79943	6.00657	0	0	0	
+4.087	0.810735	-3.79692	6.00908	0	0	0	
+4.088	0.81132	-3.79439	6.01161	0	0	0	
+4.089	0.811905	-3.79185	6.01415	0	0	0	
+4.09	0.812488	-3.7893	6.0167	0	0	0	
+4.091	0.813071	-3.78673	6.01927	0	0	0	
+4.092	0.813652	-3.78415	6.02185	0	0	0	
+4.093	0.814233	-3.78155	6.02445	0	0	0	
+4.094	0.814813	-3.77893	6.02707	0	0	0	
+4.095	0.815393	-3.7763	6.0297	0	0	0	
+4.096	0.815971	-3.77365	6.03235	0	0	0	
+4.097	0.816549	-3.77099	6.03501	0	0	0	
+4.098	0.817126	-3.76832	6.03768	0	0	0	
+4.099	0.817702	-3.76563	6.04037	0	0	0	
+4.1	0.818277	-3.76292	6.04308	0	0	0	
+4.101	0.818852	-3.7602	6.0458	0	0	0	
+4.102	0.819425	-3.75747	6.04853	0	0	0	
+4.103	0.819998	-3.75471	6.05129	0	0	0	
+4.104	0.82057	-3.75195	6.05405	0	0	0	
+4.105	0.821141	-3.74917	6.05683	0	0	0	
+4.106	0.821711	-3.74637	6.05963	0	0	0	
+4.107	0.822281	-3.74356	6.06244	0	0	0	
+4.108	0.822849	-3.74074	6.06526	0	0	0	
+4.109	0.823417	-3.73789	6.06811	0	0	0	
+4.11	0.823984	-3.73504	6.07096	0	0	0	
+4.111	0.824551	-3.73217	6.07383	0	0	0	
+4.112	0.825116	-3.72928	6.07672	0	0	0	
+4.113	0.82568	-3.72638	6.07962	0	0	0	
+4.114	0.826244	-3.72347	6.08253	0	0	0	
+4.115	0.826807	-3.72054	6.08546	0	0	0	
+4.116	0.827369	-3.71759	6.08841	0	0	0	
+4.117	0.82793	-3.71463	6.09137	0	0	0	
+4.118	0.828491	-3.71166	6.09434	0	0	0	
+4.119	0.82905	-3.70867	6.09733	0	0	0	
+4.12	0.829609	-3.70566	6.10034	0	0	0	
+4.121	0.830167	-3.70264	6.10336	0	0	0	
+4.122	0.830724	-3.69961	6.10639	0	0	0	
+4.123	0.83128	-3.69656	6.10944	0	0	0	
+4.124	0.831836	-3.6935	6.1125	0	0	0	
+4.125	0.832391	-3.69042	6.11558	0	0	0	
+4.126	0.832944	-3.68732	6.11868	0	0	0	
+4.127	0.833497	-3.68422	6.12178	0	0	0	
+4.128	0.834049	-3.68109	6.12491	0	0	0	
+4.129	0.834601	-3.67795	6.12805	0	0	0	
+4.13	0.835151	-3.6748	6.1312	0	0	0	
+4.131	0.835701	-3.67164	6.13436	0	0	0	
+4.132	0.836249	-3.66845	6.13755	0	0	0	
+4.133	0.836797	-3.66526	6.14074	0	0	0	
+4.134	0.837344	-3.66205	6.14395	0	0	0	
+4.135	0.837891	-3.65882	6.14718	0	0	0	
+4.136	0.838436	-3.65558	6.15042	0	0	0	
+4.137	0.838981	-3.65233	6.15367	0	0	0	
+4.138	0.839524	-3.64906	6.15694	0	0	0	
+4.139	0.840067	-3.64577	6.16023	0	0	0	
+4.14	0.840609	-3.64247	6.16353	0	0	0	
+4.141	0.841151	-3.63916	6.16684	0	0	0	
+4.142	0.841691	-3.63583	6.17017	0	0	0	
+4.143	0.842231	-3.63249	6.17351	0	0	0	
+4.144	0.842769	-3.62913	6.17687	0	0	0	
+4.145	0.843307	-3.62576	6.18024	0	0	0	
+4.146	0.843844	-3.62238	6.18362	0	0	0	
+4.147	0.84438	-3.61898	6.18702	0	0	0	
+4.148	0.844916	-3.61556	6.19044	0	0	0	
+4.149	0.84545	-3.61213	6.19387	0	0	0	
+4.15	0.845984	-3.60869	6.19731	0	0	0	
+4.151	0.846516	-3.60523	6.20077	0	0	0	
+4.152	0.847048	-3.60176	6.20424	0	0	0	
+4.153	0.84758	-3.59827	6.20773	0	0	0	
+4.154	0.84811	-3.59477	6.21123	0	0	0	
+4.155	0.848639	-3.59125	6.21475	0	0	0	
+4.156	0.849168	-3.58772	6.21828	0	0	0	
+4.157	0.849695	-3.58418	6.22182	0	0	0	
+4.158	0.850222	-3.58062	6.22538	0	0	0	
+4.159	0.850748	-3.57705	6.22895	0	0	0	
+4.16	0.851273	-3.57346	6.23254	0	0	0	
+4.161	0.851798	-3.56986	6.23614	0	0	0	
+4.162	0.852321	-3.56624	6.23976	0	0	0	
+4.163	0.852844	-3.56261	6.24339	0	0	0	
+4.164	0.853365	-3.55896	6.24704	0	0	0	
+4.165	0.853886	-3.55531	6.25069	0	0	0	
+4.166	0.854406	-3.55163	6.25437	0	0	0	
+4.167	0.854926	-3.54795	6.25805	0	0	0	
+4.168	0.855444	-3.54424	6.26176	0	0	0	
+4.169	0.855961	-3.54053	6.26547	0	0	0	
+4.17	0.856478	-3.5368	6.2692	0	0	0	
+4.171	0.856994	-3.53305	6.27295	0	0	0	
+4.172	0.857509	-3.5293	6.2767	0	0	0	
+4.173	0.858023	-3.52552	6.28048	0	0	0	
+4.174	0.858536	-3.52174	6.28426	0	0	0	
+4.175	0.859048	-3.51794	6.28806	0	0	0	
+4.176	0.85956	-3.51412	6.29188	0	0	0	
+4.177	0.86007	-3.5103	6.2957	0	0	0	
+4.178	0.86058	-3.50645	6.29955	0	0	0	
+4.179	0.861089	-3.5026	6.3034	0	0	0	
+4.18	0.861597	-3.49873	6.30727	0	0	0	
+4.181	0.862104	-3.49484	6.31116	0	0	0	
+4.182	0.86261	-3.49094	6.31506	0	0	0	
+4.183	0.863116	-3.48703	6.31897	0	0	0	
+4.184	0.86362	-3.4831	6.3229	0	0	0	
+4.185	0.864124	-3.47916	6.32684	0	0	0	
+4.186	0.864627	-3.47521	6.33079	0	0	0	
+4.187	0.865129	-3.47124	6.33476	0	0	0	
+4.188	0.86563	-3.46726	6.33874	0	0	0	
+4.189	0.86613	-3.46326	6.34274	0	0	0	
+4.19	0.86663	-3.45925	6.34675	0	0	0	
+4.191	0.867128	-3.45523	6.35077	0	0	0	
+4.192	0.867626	-3.45119	6.35481	0	0	0	
+4.193	0.868123	-3.44714	6.35886	0	0	0	
+4.194	0.868619	-3.44307	6.36293	0	0	0	
+4.195	0.869114	-3.439	6.367	0	0	0	
+4.196	0.869608	-3.4349	6.3711	0	0	0	
+4.197	0.870101	-3.4308	6.3752	0	0	0	
+4.198	0.870594	-3.42668	6.37932	0	0	0	
+4.199	0.871085	-3.42254	6.38346	0	0	0	
+4.2	0.871576	-3.4184	6.3876	0	0	0	
+4.201	0.872066	-3.41423	6.39177	0	0	0	
+4.202	0.872555	-3.41006	6.39594	0	0	0	
+4.203	0.873043	-3.40587	6.40013	0	0	0	
+4.204	0.87353	-3.40167	6.40433	0	0	0	
+4.205	0.874016	-3.39745	6.40855	0	0	0	
+4.206	0.874502	-3.39322	6.41278	0	0	0	
+4.207	0.874986	-3.38898	6.41702	0	0	0	
+4.208	0.87547	-3.38473	6.42127	0	0	0	
+4.209	0.875953	-3.38046	6.42554	0	0	0	
+4.21	0.876435	-3.37617	6.42983	0	0	0	
+4.211	0.876916	-3.37187	6.43413	0	0	0	
+4.212	0.877396	-3.36756	6.43844	0	0	0	
+4.213	0.877875	-3.36324	6.44276	0	0	0	
+4.214	0.878354	-3.3589	6.4471	0	0	0	
+4.215	0.878831	-3.35455	6.45145	0	0	0	
+4.216	0.879308	-3.35019	6.45581	0	0	0	
+4.217	0.879784	-3.34581	6.46019	0	0	0	
+4.218	0.880259	-3.34142	6.46458	0	0	0	
+4.219	0.880733	-3.33701	6.46899	0	0	0	
+4.22	0.881206	-3.3326	6.4734	0	0	0	
+4.221	0.881678	-3.32817	6.47783	0	0	0	
+4.222	0.88215	-3.32372	6.48228	0	0	0	
+4.223	0.88262	-3.31926	6.48674	0	0	0	
+4.224	0.88309	-3.31479	6.49121	0	0	0	
+4.225	0.883559	-3.31031	6.49569	0	0	0	
+4.226	0.884027	-3.30581	6.50019	0	0	0	
+4.227	0.884494	-3.3013	6.5047	0	0	0	
+4.228	0.88496	-3.29678	6.50922	0	0	0	
+4.229	0.885425	-3.29224	6.51376	0	0	0	
+4.23	0.885889	-3.28769	6.51831	0	0	0	
+4.231	0.886353	-3.28313	6.52287	0	0	0	
+4.232	0.886815	-3.27855	6.52745	0	0	0	
+4.233	0.887277	-3.27396	6.53204	0	0	0	
+4.234	0.887738	-3.26936	6.53664	0	0	0	
+4.235	0.888198	-3.26474	6.54126	0	0	0	
+4.236	0.888657	-3.26011	6.54589	0	0	0	
+4.237	0.889115	-3.25547	6.55053	0	0	0	
+4.238	0.889572	-3.25082	6.55518	0	0	0	
+4.239	0.890028	-3.24615	6.55985	0	0	0	
+4.24	0.890484	-3.24147	6.56453	0	0	0	
+4.241	0.890938	-3.23677	6.56923	0	0	0	
+4.242	0.891392	-3.23207	6.57393	0	0	0	
+4.243	0.891845	-3.22735	6.57865	0	0	0	
+4.244	0.892297	-3.22261	6.58339	0	0	0	
+4.245	0.892748	-3.21787	6.58813	0	0	0	
+4.246	0.893198	-3.21311	6.59289	0	0	0	
+4.247	0.893647	-3.20834	6.59766	0	0	0	
+4.248	0.894095	-3.20356	6.60244	0	0	0	
+4.249	0.894543	-3.19876	6.60724	0	0	0	
+4.25	0.894989	-3.19395	6.61205	0	0	0	
+4.251	0.895435	-3.18913	6.61687	0	0	0	
+4.252	0.89588	-3.18429	6.62171	0	0	0	
+4.253	0.896324	-3.17944	6.62656	0	0	0	
+4.254	0.896767	-3.17458	6.63142	0	0	0	
+4.255	0.897209	-3.16971	6.63629	0	0	0	
+4.256	0.89765	-3.16482	6.64118	0	0	0	
+4.257	0.89809	-3.15992	6.64608	0	0	0	
+4.258	0.898529	-3.15501	6.65099	0	0	0	
+4.259	0.898968	-3.15009	6.65591	0	0	0	
+4.26	0.899405	-3.14515	6.66085	0	0	0	
+4.261	0.899842	-3.1402	6.6658	0	0	0	
+4.262	0.900278	-3.13524	6.67076	0	0	0	
+4.263	0.900713	-3.13027	6.67573	0	0	0	
+4.264	0.901147	-3.12528	6.68072	0	0	0	
+4.265	0.90158	-3.12028	6.68572	0	0	0	
+4.266	0.902012	-3.11527	6.69073	0	0	0	
+4.267	0.902443	-3.11024	6.69576	0	0	0	
+4.268	0.902874	-3.10521	6.70079	0	0	0	
+4.269	0.903303	-3.10016	6.70584	0	0	0	
+4.27	0.903732	-3.0951	6.7109	0	0	0	
+4.271	0.904159	-3.09002	6.71598	0	0	0	
+4.272	0.904586	-3.08494	6.72106	0	0	0	
+4.273	0.905012	-3.07984	6.72616	0	0	0	
+4.274	0.905437	-3.07473	6.73127	0	0	0	
+4.275	0.905861	-3.0696	6.7364	0	0	0	
+4.276	0.906284	-3.06447	6.74153	0	0	0	
+4.277	0.906706	-3.05932	6.74668	0	0	0	
+4.278	0.907127	-3.05416	6.75184	0	0	0	
+4.279	0.907548	-3.04899	6.75701	0	0	0	
+4.28	0.907967	-3.0438	6.7622	0	0	0	
+4.281	0.908386	-3.03861	6.76739	0	0	0	
+4.282	0.908804	-3.0334	6.7726	0	0	0	
+4.283	0.90922	-3.02818	6.77782	0	0	0	
+4.284	0.909636	-3.02295	6.78305	0	0	0	
+4.285	0.910051	-3.0177	6.7883	0	0	0	
+4.286	0.910465	-3.01244	6.79356	0	0	0	
+4.287	0.910878	-3.00717	6.79883	0	0	0	
+4.288	0.91129	-3.00189	6.80411	0	0	0	
+4.289	0.911702	-2.9966	6.8094	0	0	0	
+4.29	0.912112	-2.99129	6.81471	0	0	0	
+4.291	0.912522	-2.98598	6.82002	0	0	0	
+4.292	0.91293	-2.98065	6.82535	0	0	0	
+4.293	0.913338	-2.97531	6.83069	0	0	0	
+4.294	0.913745	-2.96995	6.83605	0	0	0	
+4.295	0.91415	-2.96459	6.84141	0	0	0	
+4.296	0.914555	-2.95921	6.84679	0	0	0	
+4.297	0.914959	-2.95382	6.85218	0	0	0	
+4.298	0.915363	-2.94842	6.85758	0	0	0	
+4.299	0.915765	-2.94301	6.86299	0	0	0	
+4.3	0.916166	-2.93759	6.86841	0	0	0	
+4.301	0.916566	-2.93215	6.87385	0	0	0	
+4.302	0.916966	-2.92671	6.87929	0	0	0	
+4.303	0.917364	-2.92125	6.88475	0	0	0	
+4.304	0.917762	-2.91578	6.89022	0	0	0	
+4.305	0.918158	-2.91029	6.89571	0	0	0	
+4.306	0.918554	-2.9048	6.9012	0	0	0	
+4.307	0.918949	-2.89929	6.90671	0	0	0	
+4.308	0.919343	-2.89378	6.91222	0	0	0	
+4.309	0.919736	-2.88825	6.91775	0	0	0	
+4.31	0.920128	-2.88271	6.92329	0	0	0	
+4.311	0.920519	-2.87715	6.92885	0	0	0	
+4.312	0.920909	-2.87159	6.93441	0	0	0	
+4.313	0.921299	-2.86602	6.93998	0	0	0	
+4.314	0.921687	-2.86043	6.94557	0	0	0	
+4.315	0.922075	-2.85483	6.95117	0	0	0	
+4.316	0.922461	-2.84922	6.95678	0	0	0	
+4.317	0.922847	-2.8436	6.9624	0	0	0	
+4.318	0.923232	-2.83797	6.96803	0	0	0	
+4.319	0.923615	-2.83233	6.97367	0	0	0	
+4.32	0.923998	-2.82667	6.97933	0	0	0	
+4.321	0.92438	-2.82101	6.98499	0	0	0	
+4.322	0.924761	-2.81533	6.99067	0	0	0	
+4.323	0.925141	-2.80964	6.99636	0	0	0	
+4.324	0.92552	-2.80394	7.00206	0	0	0	
+4.325	0.925899	-2.79823	7.00777	0	0	0	
+4.326	0.926276	-2.79251	7.01349	0	0	0	
+4.327	0.926652	-2.78677	7.01923	0	0	0	
+4.328	0.927028	-2.78103	7.02497	0	0	0	
+4.329	0.927402	-2.77527	7.03073	0	0	0	
+4.33	0.927776	-2.76951	7.03649	0	0	0	
+4.331	0.928149	-2.76373	7.04227	0	0	0	
+4.332	0.92852	-2.75794	7.04806	0	0	0	
+4.333	0.928891	-2.75214	7.05386	0	0	0	
+4.334	0.929261	-2.74633	7.05967	0	0	0	
+4.335	0.92963	-2.74051	7.06549	0	0	0	
+4.336	0.929998	-2.73467	7.07133	0	0	0	
+4.337	0.930365	-2.72883	7.07717	0	0	0	
+4.338	0.930731	-2.72298	7.08302	0	0	0	
+4.339	0.931096	-2.71711	7.08889	0	0	0	
+4.34	0.931461	-2.71123	7.09477	0	0	0	
+4.341	0.931824	-2.70535	7.10065	0	0	0	
+4.342	0.932187	-2.69945	7.10655	0	0	0	
+4.343	0.932548	-2.69354	7.11246	0	0	0	
+4.344	0.932909	-2.68762	7.11838	0	0	0	
+4.345	0.933268	-2.68169	7.12431	0	0	0	
+4.346	0.933627	-2.67575	7.13025	0	0	0	
+4.347	0.933985	-2.6698	7.1362	0	0	0	
+4.348	0.934342	-2.66383	7.14217	0	0	0	
+4.349	0.934698	-2.65786	7.14814	0	0	0	
+4.35	0.935053	-2.65188	7.15412	0	0	0	
+4.351	0.935407	-2.64588	7.16012	0	0	0	
+4.352	0.93576	-2.63988	7.16612	0	0	0	
+4.353	0.936112	-2.63386	7.17214	0	0	0	
+4.354	0.936463	-2.62784	7.17816	0	0	0	
+4.355	0.936813	-2.6218	7.1842	0	0	0	
+4.356	0.937163	-2.61575	7.19025	0	0	0	
+4.357	0.937511	-2.60969	7.19631	0	0	0	
+4.358	0.937859	-2.60363	7.20237	0	0	0	
+4.359	0.938205	-2.59755	7.20845	0	0	0	
+4.36	0.938551	-2.59146	7.21454	0	0	0	
+4.361	0.938896	-2.58536	7.22064	0	0	0	
+4.362	0.939239	-2.57925	7.22675	0	0	0	
+4.363	0.939582	-2.57313	7.23287	0	0	0	
+4.364	0.939924	-2.567	7.239	0	0	0	
+4.365	0.940265	-2.56086	7.24514	0	0	0	
+4.366	0.940605	-2.55471	7.25129	0	0	0	
+4.367	0.940944	-2.54855	7.25745	0	0	0	
+4.368	0.941282	-2.54238	7.26362	0	0	0	
+4.369	0.941619	-2.5362	7.2698	0	0	0	
+4.37	0.941955	-2.53	7.276	0	0	0	
+4.371	0.942291	-2.5238	7.2822	0	0	0	
+4.372	0.942625	-2.51759	7.28841	0	0	0	
+4.373	0.942958	-2.51137	7.29463	0	0	0	
+4.374	0.943291	-2.50514	7.30086	0	0	0	
+4.375	0.943622	-2.4989	7.3071	0	0	0	
+4.376	0.943953	-2.49264	7.31336	0	0	0	
+4.377	0.944282	-2.48638	7.31962	0	0	0	
+4.378	0.944611	-2.48011	7.32589	0	0	0	
+4.379	0.944939	-2.47383	7.33217	0	0	0	
+4.38	0.945266	-2.46754	7.33846	0	0	0	
+4.381	0.945591	-2.46124	7.34476	0	0	0	
+4.382	0.945916	-2.45492	7.35108	0	0	0	
+4.383	0.94624	-2.4486	7.3574	0	0	0	
+4.384	0.946563	-2.44227	7.36373	0	0	0	
+4.385	0.946885	-2.43593	7.37007	0	0	0	
+4.386	0.947206	-2.42958	7.37642	0	0	0	
+4.387	0.947526	-2.42322	7.38278	0	0	0	
+4.388	0.947846	-2.41685	7.38915	0	0	0	
+4.389	0.948164	-2.41047	7.39553	0	0	0	
+4.39	0.948481	-2.40408	7.40192	0	0	0	
+4.391	0.948798	-2.39769	7.40831	0	0	0	
+4.392	0.949113	-2.39128	7.41472	0	0	0	
+4.393	0.949427	-2.38486	7.42114	0	0	0	
+4.394	0.949741	-2.37843	7.42757	0	0	0	
+4.395	0.950054	-2.37199	7.43401	0	0	0	
+4.396	0.950365	-2.36555	7.44045	0	0	0	
+4.397	0.950676	-2.35909	7.44691	0	0	0	
+4.398	0.950986	-2.35263	7.45337	0	0	0	
+4.399	0.951294	-2.34615	7.45985	0	0	0	
+4.4	0.951602	-2.33967	7.46633	0	0	0	
+4.401	0.951909	-2.33318	7.47282	0	0	0	
+4.402	0.952215	-2.32667	7.47933	0	0	0	
+4.403	0.95252	-2.32016	7.48584	0	0	0	
+4.404	0.952824	-2.31364	7.49236	0	0	0	
+4.405	0.953127	-2.30711	7.49889	0	0	0	
+4.406	0.953429	-2.30057	7.50543	0	0	0	
+4.407	0.95373	-2.29402	7.51198	0	0	0	
+4.408	0.95403	-2.28746	7.51854	0	0	0	
+4.409	0.954329	-2.28089	7.52511	0	0	0	
+4.41	0.954628	-2.27432	7.53168	0	0	0	
+4.411	0.954925	-2.26773	7.53827	0	0	0	
+4.412	0.955221	-2.26114	7.54486	0	0	0	
+4.413	0.955517	-2.25453	7.55147	0	0	0	
+4.414	0.955811	-2.24792	7.55808	0	0	0	
+4.415	0.956105	-2.2413	7.5647	0	0	0	
+4.416	0.956397	-2.23467	7.57133	0	0	0	
+4.417	0.956689	-2.22803	7.57797	0	0	0	
+4.418	0.95698	-2.22138	7.58462	0	0	0	
+4.419	0.957269	-2.21472	7.59128	0	0	0	
+4.42	0.957558	-2.20806	7.59794	0	0	0	
+4.421	0.957846	-2.20138	7.60462	0	0	0	
+4.422	0.958133	-2.1947	7.6113	0	0	0	
+4.423	0.958418	-2.18801	7.61799	0	0	0	
+4.424	0.958703	-2.1813	7.6247	0	0	0	
+4.425	0.958987	-2.17459	7.63141	0	0	0	
+4.426	0.95927	-2.16787	7.63813	0	0	0	
+4.427	0.959552	-2.16115	7.64485	0	0	0	
+4.428	0.959833	-2.15441	7.65159	0	0	0	
+4.429	0.960113	-2.14767	7.65833	0	0	0	
+4.43	0.960392	-2.14091	7.66509	0	0	0	
+4.431	0.960671	-2.13415	7.67185	0	0	0	
+4.432	0.960948	-2.12738	7.67862	0	0	0	
+4.433	0.961224	-2.1206	7.6854	0	0	0	
+4.434	0.961499	-2.11381	7.69219	0	0	0	
+4.435	0.961774	-2.10702	7.69898	0	0	0	
+4.436	0.962047	-2.10021	7.70579	0	0	0	
+4.437	0.962319	-2.0934	7.7126	0	0	0	
+4.438	0.962591	-2.08658	7.71942	0	0	0	
+4.439	0.962861	-2.07975	7.72625	0	0	0	
+4.44	0.963131	-2.07291	7.73309	0	0	0	
+4.441	0.963399	-2.06607	7.73993	0	0	0	
+4.442	0.963667	-2.05921	7.74679	0	0	0	
+4.443	0.963934	-2.05235	7.75365	0	0	0	
+4.444	0.964199	-2.04548	7.76052	0	0	0	
+4.445	0.964464	-2.0386	7.7674	0	0	0	
+4.446	0.964728	-2.03171	7.77429	0	0	0	
+4.447	0.964991	-2.02482	7.78118	0	0	0	
+4.448	0.965252	-2.01791	7.78809	0	0	0	
+4.449	0.965513	-2.011	7.795	0	0	0	
+4.45	0.965773	-2.00408	7.80192	0	0	0	
+4.451	0.966032	-1.99716	7.80884	0	0	0	
+4.452	0.96629	-1.99022	7.81578	0	0	0	
+4.453	0.966547	-1.98328	7.82272	0	0	0	
+4.454	0.966803	-1.97633	7.82967	0	0	0	
+4.455	0.967058	-1.96937	7.83663	0	0	0	
+4.456	0.967312	-1.9624	7.8436	0	0	0	
+4.457	0.967565	-1.95542	7.85058	0	0	0	
+4.458	0.967817	-1.94844	7.85756	0	0	0	
+4.459	0.968068	-1.94145	7.86455	0	0	0	
+4.46	0.968319	-1.93445	7.87155	0	0	0	
+4.461	0.968568	-1.92745	7.87855	0	0	0	
+4.462	0.968816	-1.92043	7.88557	0	0	0	
+4.463	0.969063	-1.91341	7.89259	0	0	0	
+4.464	0.96931	-1.90638	7.89962	0	0	0	
+4.465	0.969555	-1.89935	7.90665	0	0	0	
+4.466	0.969799	-1.8923	7.9137	0	0	0	
+4.467	0.970043	-1.88525	7.92075	0	0	0	
+4.468	0.970285	-1.87819	7.92781	0	0	0	
+4.469	0.970527	-1.87112	7.93488	0	0	0	
+4.47	0.970767	-1.86405	7.94195	0	0	0	
+4.471	0.971007	-1.85697	7.94903	0	0	0	
+4.472	0.971245	-1.84988	7.95612	0	0	0	
+4.473	0.971483	-1.84278	7.96322	0	0	0	
+4.474	0.97172	-1.83568	7.97032	0	0	0	
+4.475	0.971955	-1.82856	7.97744	0	0	0	
+4.476	0.97219	-1.82145	7.98455	0	0	0	
+4.477	0.972424	-1.81432	7.99168	0	0	0	
+4.478	0.972656	-1.80719	7.99881	0	0	0	
+4.479	0.972888	-1.80005	8.00595	0	0	0	
+4.48	0.973119	-1.7929	8.0131	0	0	0	
+4.481	0.973349	-1.78574	8.02026	0	0	0	
+4.482	0.973578	-1.77858	8.02742	0	0	0	
+4.483	0.973806	-1.77141	8.03459	0	0	0	
+4.484	0.974032	-1.76423	8.04177	0	0	0	
+4.485	0.974258	-1.75705	8.04895	0	0	0	
+4.486	0.974483	-1.74986	8.05614	0	0	0	
+4.487	0.974707	-1.74266	8.06334	0	0	0	
+4.488	0.97493	-1.73546	8.07054	0	0	0	
+4.489	0.975152	-1.72825	8.07775	0	0	0	
+4.49	0.975373	-1.72103	8.08497	0	0	0	
+4.491	0.975593	-1.7138	8.0922	0	0	0	
+4.492	0.975812	-1.70657	8.09943	0	0	0	
+4.493	0.976031	-1.69933	8.10667	0	0	0	
+4.494	0.976248	-1.69209	8.11391	0	0	0	
+4.495	0.976464	-1.68484	8.12116	0	0	0	
+4.496	0.976679	-1.67758	8.12842	0	0	0	
+4.497	0.976893	-1.67031	8.13569	0	0	0	
+4.498	0.977107	-1.66304	8.14296	0	0	0	
+4.499	0.977319	-1.65576	8.15024	0	0	0	
+4.5	0.97753	-1.64847	8.15753	0	0	0	
+4.501	0.97774	-1.64118	8.16482	0	0	0	
+4.502	0.97795	-1.63388	8.17212	0	0	0	
+4.503	0.978158	-1.62658	8.17942	0	0	0	
+4.504	0.978365	-1.61927	8.18673	0	0	0	
+4.505	0.978572	-1.61195	8.19405	0	0	0	
+4.506	0.978777	-1.60462	8.20138	0	0	0	
+4.507	0.978982	-1.59729	8.20871	0	0	0	
+4.508	0.979185	-1.58995	8.21605	0	0	0	
+4.509	0.979388	-1.58261	8.22339	0	0	0	
+4.51	0.979589	-1.57526	8.23074	0	0	0	
+4.511	0.97979	-1.5679	8.2381	0	0	0	
+4.512	0.979989	-1.56054	8.24546	0	0	0	
+4.513	0.980188	-1.55317	8.25283	0	0	0	
+4.514	0.980385	-1.54579	8.26021	0	0	0	
+4.515	0.980582	-1.53841	8.26759	0	0	0	
+4.516	0.980778	-1.53103	8.27497	0	0	0	
+4.517	0.980972	-1.52363	8.28237	0	0	0	
+4.518	0.981166	-1.51623	8.28977	0	0	0	
+4.519	0.981359	-1.50883	8.29717	0	0	0	
+4.52	0.98155	-1.50141	8.30459	0	0	0	
+4.521	0.981741	-1.494	8.312	0	0	0	
+4.522	0.981931	-1.48657	8.31943	0	0	0	
+4.523	0.982119	-1.47914	8.32686	0	0	0	
+4.524	0.982307	-1.47171	8.33429	0	0	0	
+4.525	0.982494	-1.46426	8.34174	0	0	0	
+4.526	0.98268	-1.45682	8.34918	0	0	0	
+4.527	0.982865	-1.44936	8.35664	0	0	0	
+4.528	0.983048	-1.4419	8.3641	0	0	0	
+4.529	0.983231	-1.43444	8.37156	0	0	0	
+4.53	0.983413	-1.42697	8.37903	0	0	0	
+4.531	0.983594	-1.41949	8.38651	0	0	0	
+4.532	0.983774	-1.41201	8.39399	0	0	0	
+4.533	0.983953	-1.40452	8.40148	0	0	0	
+4.534	0.984131	-1.39703	8.40897	0	0	0	
+4.535	0.984308	-1.38953	8.41647	0	0	0	
+4.536	0.984484	-1.38202	8.42398	0	0	0	
+4.537	0.984659	-1.37451	8.43149	0	0	0	
+4.538	0.984833	-1.367	8.439	0	0	0	
+4.539	0.985006	-1.35948	8.44652	0	0	0	
+4.54	0.985178	-1.35195	8.45405	0	0	0	
+4.541	0.985349	-1.34442	8.46158	0	0	0	
+4.542	0.985519	-1.33688	8.46912	0	0	0	
+4.543	0.985688	-1.32934	8.47666	0	0	0	
+4.544	0.985856	-1.32179	8.48421	0	0	0	
+4.545	0.986023	-1.31424	8.49176	0	0	0	
+4.546	0.986189	-1.30668	8.49932	0	0	0	
+4.547	0.986354	-1.29912	8.50688	0	0	0	
+4.548	0.986519	-1.29155	8.51445	0	0	0	
+4.549	0.986682	-1.28397	8.52203	0	0	0	
+4.55	0.986844	-1.27639	8.52961	0	0	0	
+4.551	0.987005	-1.26881	8.53719	0	0	0	
+4.552	0.987165	-1.26122	8.54478	0	0	0	
+4.553	0.987324	-1.25363	8.55237	0	0	0	
+4.554	0.987483	-1.24603	8.55997	0	0	0	
+4.555	0.98764	-1.23842	8.56758	0	0	0	
+4.556	0.987796	-1.23081	8.57519	0	0	0	
+4.557	0.987951	-1.2232	8.5828	0	0	0	
+4.558	0.988106	-1.21558	8.59042	0	0	0	
+4.559	0.988259	-1.20795	8.59805	0	0	0	
+4.56	0.988411	-1.20033	8.60567	0	0	0	
+4.561	0.988563	-1.19269	8.61331	0	0	0	
+4.562	0.988713	-1.18505	8.62095	0	0	0	
+4.563	0.988862	-1.17741	8.62859	0	0	0	
+4.564	0.989011	-1.16976	8.63624	0	0	0	
+4.565	0.989158	-1.16211	8.64389	0	0	0	
+4.566	0.989304	-1.15445	8.65155	0	0	0	
+4.567	0.98945	-1.14679	8.65921	0	0	0	
+4.568	0.989594	-1.13912	8.66688	0	0	0	
+4.569	0.989737	-1.13145	8.67455	0	0	0	
+4.57	0.98988	-1.12378	8.68222	0	0	0	
+4.571	0.990021	-1.1161	8.6899	0	0	0	
+4.572	0.990162	-1.10841	8.69759	0	0	0	
+4.573	0.990301	-1.10072	8.70528	0	0	0	
+4.574	0.99044	-1.09303	8.71297	0	0	0	
+4.575	0.990577	-1.08533	8.72067	0	0	0	
+4.576	0.990713	-1.07763	8.72837	0	0	0	
+4.577	0.990849	-1.06992	8.73608	0	0	0	
+4.578	0.990983	-1.06221	8.74379	0	0	0	
+4.579	0.991117	-1.0545	8.7515	0	0	0	
+4.58	0.991249	-1.04678	8.75922	0	0	0	
+4.581	0.991381	-1.03906	8.76694	0	0	0	
+4.582	0.991511	-1.03133	8.77467	0	0	0	
+4.583	0.991641	-1.0236	8.7824	0	0	0	
+4.584	0.991769	-1.01586	8.79014	0	0	0	
+4.585	0.991897	-1.00812	8.79788	0	0	0	
+4.586	0.992024	-1.00038	8.80562	0	0	0	
+4.587	0.992149	-0.992631	8.81337	0	0	0	
+4.588	0.992274	-0.984879	8.82112	0	0	0	
+4.589	0.992397	-0.977123	8.82888	0	0	0	
+4.59	0.99252	-0.969364	8.83664	0	0	0	
+4.591	0.992641	-0.9616	8.8444	0	0	0	
+4.592	0.992762	-0.953833	8.85217	0	0	0	
+4.593	0.992882	-0.946062	8.85994	0	0	0	
+4.594	0.993	-0.938287	8.86771	0	0	0	
+4.595	0.993118	-0.930508	8.87549	0	0	0	
+4.596	0.993234	-0.922726	8.88327	0	0	0	
+4.597	0.99335	-0.91494	8.89106	0	0	0	
+4.598	0.993465	-0.90715	8.89885	0	0	0	
+4.599	0.993578	-0.899357	8.90664	0	0	0	
+4.6	0.993691	-0.89156	8.91444	0	0	0	
+4.601	0.993803	-0.883759	8.92224	0	0	0	
+4.602	0.993913	-0.875955	8.93004	0	0	0	
+4.603	0.994023	-0.868148	8.93785	0	0	0	
+4.604	0.994132	-0.860336	8.94566	0	0	0	
+4.605	0.994239	-0.852522	8.95348	0	0	0	
+4.606	0.994346	-0.844704	8.9613	0	0	0	
+4.607	0.994452	-0.836883	8.96912	0	0	0	
+4.608	0.994556	-0.829058	8.97694	0	0	0	
+4.609	0.99466	-0.82123	8.98477	0	0	0	
+4.61	0.994763	-0.813399	8.9926	0	0	0	
+4.611	0.994865	-0.805565	9.00044	0	0	0	
+4.612	0.994965	-0.797727	9.00827	0	0	0	
+4.613	0.995065	-0.789886	9.01611	0	0	0	
+4.614	0.995164	-0.782042	9.02396	0	0	0	
+4.615	0.995261	-0.774195	9.03181	0	0	0	
+4.616	0.995358	-0.766345	9.03966	0	0	0	
+4.617	0.995454	-0.758491	9.04751	0	0	0	
+4.618	0.995549	-0.750635	9.05537	0	0	0	
+4.619	0.995642	-0.742775	9.06322	0	0	0	
+4.62	0.995735	-0.734913	9.07109	0	0	0	
+4.621	0.995827	-0.727048	9.07895	0	0	0	
+4.622	0.995918	-0.71918	9.08682	0	0	0	
+4.623	0.996007	-0.711309	9.09469	0	0	0	
+4.624	0.996096	-0.703435	9.10257	0	0	0	
+4.625	0.996184	-0.695558	9.11044	0	0	0	
+4.626	0.996271	-0.687678	9.11832	0	0	0	
+4.627	0.996357	-0.679796	9.1262	0	0	0	
+4.628	0.996441	-0.671911	9.13409	0	0	0	
+4.629	0.996525	-0.664024	9.14198	0	0	0	
+4.63	0.996608	-0.656133	9.14987	0	0	0	
+4.631	0.99669	-0.64824	9.15776	0	0	0	
+4.632	0.996771	-0.640345	9.16566	0	0	0	
+4.633	0.99685	-0.632447	9.17355	0	0	0	
+4.634	0.996929	-0.624546	9.18145	0	0	0	
+4.635	0.997007	-0.616643	9.18936	0	0	0	
+4.636	0.997084	-0.608737	9.19726	0	0	0	
+4.637	0.99716	-0.600829	9.20517	0	0	0	
+4.638	0.997234	-0.592919	9.21308	0	0	0	
+4.639	0.997308	-0.585006	9.22099	0	0	0	
+4.64	0.997381	-0.577091	9.22891	0	0	0	
+4.641	0.997453	-0.569173	9.23683	0	0	0	
+4.642	0.997524	-0.561254	9.24475	0	0	0	
+4.643	0.997594	-0.553332	9.25267	0	0	0	
+4.644	0.997662	-0.545408	9.26059	0	0	0	
+4.645	0.99773	-0.537481	9.26852	0	0	0	
+4.646	0.997797	-0.529553	9.27645	0	0	0	
+4.647	0.997863	-0.521622	9.28438	0	0	0	
+4.648	0.997928	-0.513689	9.29231	0	0	0	
+4.649	0.997992	-0.505754	9.30025	0	0	0	
+4.65	0.998054	-0.497818	9.30818	0	0	0	
+4.651	0.998116	-0.489879	9.31612	0	0	0	
+4.652	0.998177	-0.481938	9.32406	0	0	0	
+4.653	0.998237	-0.473995	9.332	0	0	0	
+4.654	0.998296	-0.466051	9.33995	0	0	0	
+4.655	0.998354	-0.458104	9.3479	0	0	0	
+4.656	0.998411	-0.450156	9.35584	0	0	0	
+4.657	0.998466	-0.442206	9.36379	0	0	0	
+4.658	0.998521	-0.434254	9.37175	0	0	0	
+4.659	0.998575	-0.426301	9.3797	0	0	0	
+4.66	0.998628	-0.418345	9.38765	0	0	0	
+4.661	0.99868	-0.410388	9.39561	0	0	0	
+4.662	0.998731	-0.40243	9.40357	0	0	0	
+4.663	0.998781	-0.39447	9.41153	0	0	0	
+4.664	0.998829	-0.386508	9.41949	0	0	0	
+4.665	0.998877	-0.378545	9.42746	0	0	0	
+4.666	0.998924	-0.37058	9.43542	0	0	0	
+4.667	0.99897	-0.362613	9.44339	0	0	0	
+4.668	0.999015	-0.354646	9.45135	0	0	0	
+4.669	0.999059	-0.346676	9.45932	0	0	0	
+4.67	0.999102	-0.338706	9.46729	0	0	0	
+4.671	0.999144	-0.330734	9.47527	0	0	0	
+4.672	0.999184	-0.322761	9.48324	0	0	0	
+4.673	0.999224	-0.314786	9.49121	0	0	0	
+4.674	0.999263	-0.30681	9.49919	0	0	0	
+4.675	0.999301	-0.298833	9.50717	0	0	0	
+4.676	0.999338	-0.290855	9.51515	0	0	0	
+4.677	0.999374	-0.282876	9.52312	0	0	0	
+4.678	0.999409	-0.274895	9.53111	0	0	0	
+4.679	0.999443	-0.266913	9.53909	0	0	0	
+4.68	0.999476	-0.258931	9.54707	0	0	0	
+4.681	0.999507	-0.250947	9.55505	0	0	0	
+4.682	0.999538	-0.242962	9.56304	0	0	0	
+4.683	0.999568	-0.234976	9.57102	0	0	0	
+4.684	0.999597	-0.22699	9.57901	0	0	0	
+4.685	0.999625	-0.219002	9.587	0	0	0	
+4.686	0.999652	-0.211014	9.59499	0	0	0	
+4.687	0.999678	-0.203025	9.60298	0	0	0	
+4.688	0.999703	-0.195034	9.61097	0	0	0	
+4.689	0.999726	-0.187044	9.61896	0	0	0	
+4.69	0.999749	-0.179052	9.62695	0	0	0	
+4.691	0.999771	-0.17106	9.63494	0	0	0	
+4.692	0.999792	-0.163067	9.64293	0	0	0	
+4.693	0.999812	-0.155073	9.65093	0	0	0	
+4.694	0.999831	-0.147079	9.65892	0	0	0	
+4.695	0.999849	-0.139084	9.66692	0	0	0	
+4.696	0.999866	-0.131088	9.67491	0	0	0	
+4.697	0.999882	-0.123092	9.68291	0	0	0	
+4.698	0.999896	-0.115096	9.6909	0	0	0	
+4.699	0.99991	-0.107099	9.6989	0	0	0	
+4.7	0.999923	-0.0991017	9.7069	0	0	0	
+4.701	0.999935	-0.091104	9.7149	0	0	0	
+4.702	0.999946	-0.0831059	9.72289	0	0	0	
+4.703	0.999956	-0.0751074	9.73089	0	0	0	
+4.704	0.999965	-0.0671087	9.73889	0	0	0	
+4.705	0.999973	-0.0591097	9.74689	0	0	0	
+4.706	0.99998	-0.0511105	9.75489	0	0	0	
+4.707	0.999985	-0.043111	9.76289	0	0	0	
+4.708	0.99999	-0.0351114	9.77089	0	0	0	
+4.709	0.999994	-0.0271116	9.77889	0	0	0	
+4.71	0.999997	-0.0191118	9.78689	0	0	0	
+4.711	0.999999	-0.0111118	9.79489	0	0	0	
+4.712	1	-0.00311184	9.80289	0	0	0	
+4.713	1	0.00488816	9.81089	0	0	0	
+4.714	0.999999	0.0128881	9.81889	0	0	0	
+4.715	0.999997	0.0208881	9.82689	0	0	0	
+4.716	0.999993	0.0288879	9.83489	0	0	0	
+4.717	0.999989	0.0368876	9.84289	0	0	0	
+4.718	0.999984	0.0448872	9.85089	0	0	0	
+4.719	0.999978	0.0528866	9.85889	0	0	0	
+4.72	0.999971	0.0608858	9.86689	0	0	0	
+4.721	0.999963	0.0688848	9.87488	0	0	0	
+4.722	0.999954	0.0768834	9.88288	0	0	0	
+4.723	0.999944	0.0848818	9.89088	0	0	0	
+4.724	0.999933	0.0928798	9.89888	0	0	0	
+4.725	0.99992	0.100877	9.90688	0	0	0	
+4.726	0.999907	0.108875	9.91487	0	0	0	
+4.727	0.999893	0.116872	9.92287	0	0	0	
+4.728	0.999878	0.124868	9.93087	0	0	0	
+4.729	0.999862	0.132864	9.93886	0	0	0	
+4.73	0.999845	0.140859	9.94686	0	0	0	
+4.731	0.999827	0.148854	9.95485	0	0	0	
+4.732	0.999808	0.156848	9.96285	0	0	0	
+4.733	0.999788	0.164841	9.97084	0	0	0	
+4.734	0.999766	0.172834	9.97883	0	0	0	
+4.735	0.999744	0.180827	9.98683	0	0	0	
+4.736	0.999721	0.188818	9.99482	0	0	0	
+4.737	0.999697	0.196809	10.0028	0	0	0	
+4.738	0.999672	0.204799	10.0108	0	0	0	
+4.739	0.999646	0.212788	10.0188	0	0	0	
+4.74	0.999619	0.220776	10.0268	0	0	0	
+4.741	0.999591	0.228763	10.0348	0	0	0	
+4.742	0.999562	0.23675	10.0427	0	0	0	
+4.743	0.999532	0.244735	10.0507	0	0	0	
+4.744	0.9995	0.25272	10.0587	0	0	0	
+4.745	0.999468	0.260703	10.0667	0	0	0	
+4.746	0.999435	0.268686	10.0747	0	0	0	
+4.747	0.999401	0.276667	10.0827	0	0	0	
+4.748	0.999366	0.284647	10.0906	0	0	0	
+4.749	0.99933	0.292627	10.0986	0	0	0	
+4.75	0.999293	0.300604	10.1066	0	0	0	
+4.751	0.999255	0.308581	10.1146	0	0	0	
+4.752	0.999216	0.316557	10.1226	0	0	0	
+4.753	0.999175	0.324531	10.1305	0	0	0	
+4.754	0.999134	0.332504	10.1385	0	0	0	
+4.755	0.999092	0.340476	10.1465	0	0	0	
+4.756	0.999049	0.348446	10.1544	0	0	0	
+4.757	0.999005	0.356415	10.1624	0	0	0	
+4.758	0.99896	0.364382	10.1704	0	0	0	
+4.759	0.998914	0.372348	10.1783	0	0	0	
+4.76	0.998867	0.380313	10.1863	0	0	0	
+4.761	0.998819	0.388276	10.1943	0	0	0	
+4.762	0.99877	0.396237	10.2022	0	0	0	
+4.763	0.99872	0.404197	10.2102	0	0	0	
+4.764	0.998668	0.412155	10.2182	0	0	0	
+4.765	0.998616	0.420112	10.2261	0	0	0	
+4.766	0.998563	0.428067	10.2341	0	0	0	
+4.767	0.998509	0.43602	10.242	0	0	0	
+4.768	0.998454	0.443971	10.25	0	0	0	
+4.769	0.998398	0.451921	10.2579	0	0	0	
+4.77	0.998341	0.459869	10.2659	0	0	0	
+4.771	0.998283	0.467815	10.2738	0	0	0	
+4.772	0.998224	0.475759	10.2818	0	0	0	
+4.773	0.998164	0.483701	10.2897	0	0	0	
+4.774	0.998103	0.491642	10.2976	0	0	0	
+4.775	0.998041	0.49958	10.3056	0	0	0	
+4.776	0.997978	0.507517	10.3135	0	0	0	
+4.777	0.997913	0.515451	10.3215	0	0	0	
+4.778	0.997848	0.523383	10.3294	0	0	0	
+4.779	0.997782	0.531313	10.3373	0	0	0	
+4.78	0.997715	0.539241	10.3452	0	0	0	
+4.781	0.997647	0.547167	10.3532	0	0	0	
+4.782	0.997578	0.555091	10.3611	0	0	0	
+4.783	0.997508	0.563012	10.369	0	0	0	
+4.784	0.997437	0.570932	10.3769	0	0	0	
+4.785	0.997365	0.578849	10.3848	0	0	0	
+4.786	0.997292	0.586763	10.3928	0	0	0	
+4.787	0.997218	0.594675	10.4007	0	0	0	
+4.788	0.997143	0.602585	10.4086	0	0	0	
+4.789	0.997067	0.610493	10.4165	0	0	0	
+4.79	0.99699	0.618398	10.4244	0	0	0	
+4.791	0.996912	0.6263	10.4323	0	0	0	
+4.792	0.996833	0.634201	10.4402	0	0	0	
+4.793	0.996753	0.642098	10.4481	0	0	0	
+4.794	0.996672	0.649993	10.456	0	0	0	
+4.795	0.99659	0.657885	10.4639	0	0	0	
+4.796	0.996507	0.665775	10.4718	0	0	0	
+4.797	0.996423	0.673662	10.4797	0	0	0	
+4.798	0.996338	0.681547	10.4875	0	0	0	
+4.799	0.996252	0.689428	10.4954	0	0	0	
+4.8	0.996165	0.697307	10.5033	0	0	0	
+4.801	0.996077	0.705183	10.5112	0	0	0	
+4.802	0.995988	0.713057	10.5191	0	0	0	
+4.803	0.995898	0.720927	10.5269	0	0	0	
+4.804	0.995807	0.728794	10.5348	0	0	0	
+4.805	0.995715	0.736659	10.5427	0	0	0	
+4.806	0.995622	0.744521	10.5505	0	0	0	
+4.807	0.995528	0.75238	10.5584	0	0	0	
+4.808	0.995433	0.760235	10.5662	0	0	0	
+4.809	0.995337	0.768088	10.5741	0	0	0	
+4.81	0.99524	0.775937	10.5819	0	0	0	
+4.811	0.995142	0.783784	10.5898	0	0	0	
+4.812	0.995043	0.791627	10.5976	0	0	0	
+4.813	0.994943	0.799467	10.6055	0	0	0	
+4.814	0.994842	0.807304	10.6133	0	0	0	
+4.815	0.99474	0.815138	10.6211	0	0	0	
+4.816	0.994637	0.822969	10.629	0	0	0	
+4.817	0.994533	0.830796	10.6368	0	0	0	
+4.818	0.994428	0.83862	10.6446	0	0	0	
+4.819	0.994322	0.84644	10.6524	0	0	0	
+4.82	0.994216	0.854257	10.6603	0	0	0	
+4.821	0.994108	0.862071	10.6681	0	0	0	
+4.822	0.993999	0.869881	10.6759	0	0	0	
+4.823	0.993889	0.877688	10.6837	0	0	0	
+4.824	0.993778	0.885491	10.6915	0	0	0	
+4.825	0.993666	0.893291	10.6993	0	0	0	
+4.826	0.993553	0.901087	10.7071	0	0	0	
+4.827	0.993439	0.90888	10.7149	0	0	0	
+4.828	0.993324	0.916669	10.7227	0	0	0	
+4.829	0.993209	0.924454	10.7305	0	0	0	
+4.83	0.993092	0.932236	10.7382	0	0	0	
+4.831	0.992974	0.940013	10.746	0	0	0	
+4.832	0.992855	0.947788	10.7538	0	0	0	
+4.833	0.992735	0.955558	10.7616	0	0	0	
+4.834	0.992614	0.963324	10.7693	0	0	0	
+4.835	0.992493	0.971087	10.7771	0	0	0	
+4.836	0.99237	0.978846	10.7848	0	0	0	
+4.837	0.992246	0.9866	10.7926	0	0	0	
+4.838	0.992121	0.994351	10.8004	0	0	0	
+4.839	0.991996	1.0021	10.8081	0	0	0	
+4.84	0.991869	1.00984	10.8158	0	0	0	
+4.841	0.991741	1.01758	10.8236	0	0	0	
+4.842	0.991612	1.02531	10.8313	0	0	0	
+4.843	0.991482	1.03305	10.839	0	0	0	
+4.844	0.991352	1.04077	10.8468	0	0	0	
+4.845	0.99122	1.04849	10.8545	0	0	0	
+4.846	0.991087	1.05621	10.8622	0	0	0	
+4.847	0.990954	1.06393	10.8699	0	0	0	
+4.848	0.990819	1.07164	10.8776	0	0	0	
+4.849	0.990683	1.07934	10.8853	0	0	0	
+4.85	0.990547	1.08704	10.893	0	0	0	
+4.851	0.990409	1.09474	10.9007	0	0	0	
+4.852	0.99027	1.10243	10.9084	0	0	0	
+4.853	0.990131	1.11012	10.9161	0	0	0	
+4.854	0.98999	1.1178	10.9238	0	0	0	
+4.855	0.989848	1.12548	10.9315	0	0	0	
+4.856	0.989706	1.13316	10.9392	0	0	0	
+4.857	0.989562	1.14083	10.9468	0	0	0	
+4.858	0.989417	1.14849	10.9545	0	0	0	
+4.859	0.989272	1.15615	10.9622	0	0	0	
+4.86	0.989125	1.16381	10.9698	0	0	0	
+4.861	0.988978	1.17146	10.9775	0	0	0	
+4.862	0.988829	1.17911	10.9851	0	0	0	
+4.863	0.98868	1.18675	10.9927	0	0	0	
+4.864	0.988529	1.19439	11.0004	0	0	0	
+4.865	0.988378	1.20202	11.008	0	0	0	
+4.866	0.988225	1.20965	11.0156	0	0	0	
+4.867	0.988072	1.21727	11.0233	0	0	0	
+4.868	0.987917	1.22489	11.0309	0	0	0	
+4.869	0.987762	1.2325	11.0385	0	0	0	
+4.87	0.987605	1.24011	11.0461	0	0	0	
+4.871	0.987448	1.24771	11.0537	0	0	0	
+4.872	0.987289	1.25531	11.0613	0	0	0	
+4.873	0.98713	1.26291	11.0689	0	0	0	
+4.874	0.986969	1.27049	11.0765	0	0	0	
+4.875	0.986808	1.27808	11.0841	0	0	0	
+4.876	0.986646	1.28565	11.0917	0	0	0	
+4.877	0.986482	1.29323	11.0992	0	0	0	
+4.878	0.986318	1.3008	11.1068	0	0	0	
+4.879	0.986152	1.30836	11.1144	0	0	0	
+4.88	0.985986	1.31592	11.1219	0	0	0	
+4.881	0.985819	1.32347	11.1295	0	0	0	
+4.882	0.985651	1.33101	11.137	0	0	0	
+4.883	0.985481	1.33856	11.1446	0	0	0	
+4.884	0.985311	1.34609	11.1521	0	0	0	
+4.885	0.98514	1.35362	11.1596	0	0	0	
+4.886	0.984967	1.36115	11.1671	0	0	0	
+4.887	0.984794	1.36867	11.1747	0	0	0	
+4.888	0.98462	1.37618	11.1822	0	0	0	
+4.889	0.984445	1.38369	11.1897	0	0	0	
+4.89	0.984269	1.39119	11.1972	0	0	0	
+4.891	0.984091	1.39869	11.2047	0	0	0	
+4.892	0.983913	1.40618	11.2122	0	0	0	
+4.893	0.983734	1.41367	11.2197	0	0	0	
+4.894	0.983554	1.42115	11.2272	0	0	0	
+4.895	0.983373	1.42863	11.2346	0	0	0	
+4.896	0.983191	1.4361	11.2421	0	0	0	
+4.897	0.983008	1.44356	11.2496	0	0	0	
+4.898	0.982824	1.45102	11.257	0	0	0	
+4.899	0.982639	1.45847	11.2645	0	0	0	
+4.9	0.982453	1.46592	11.2719	0	0	0	
+4.901	0.982266	1.47336	11.2794	0	0	0	
+4.902	0.982078	1.48079	11.2868	0	0	0	
+4.903	0.981889	1.48822	11.2942	0	0	0	
+4.904	0.981699	1.49564	11.3016	0	0	0	
+4.905	0.981508	1.50306	11.3091	0	0	0	
+4.906	0.981316	1.51047	11.3165	0	0	0	
+4.907	0.981123	1.51788	11.3239	0	0	0	
+4.908	0.980929	1.52527	11.3313	0	0	0	
+4.909	0.980734	1.53267	11.3387	0	0	0	
+4.91	0.980538	1.54005	11.3461	0	0	0	
+4.911	0.980342	1.54743	11.3534	0	0	0	
+4.912	0.980144	1.55481	11.3608	0	0	0	
+4.913	0.979945	1.56217	11.3682	0	0	0	
+4.914	0.979745	1.56954	11.3755	0	0	0	
+4.915	0.979545	1.57689	11.3829	0	0	0	
+4.916	0.979343	1.58424	11.3902	0	0	0	
+4.917	0.97914	1.59158	11.3976	0	0	0	
+4.918	0.978936	1.59892	11.4049	0	0	0	
+4.919	0.978732	1.60625	11.4122	0	0	0	
+4.92	0.978526	1.61357	11.4196	0	0	0	
+4.921	0.97832	1.62089	11.4269	0	0	0	
+4.922	0.978112	1.6282	11.4342	0	0	0	
+4.923	0.977903	1.6355	11.4415	0	0	0	
+4.924	0.977694	1.6428	11.4488	0	0	0	
+4.925	0.977483	1.65009	11.4561	0	0	0	
+4.926	0.977272	1.65738	11.4634	0	0	0	
+4.927	0.977059	1.66465	11.4707	0	0	0	
+4.928	0.976846	1.67193	11.4779	0	0	0	
+4.929	0.976631	1.67919	11.4852	0	0	0	
+4.93	0.976416	1.68645	11.4924	0	0	0	
+4.931	0.9762	1.6937	11.4997	0	0	0	
+4.932	0.975982	1.70094	11.5069	0	0	0	
+4.933	0.975764	1.70818	11.5142	0	0	0	
+4.934	0.975545	1.71541	11.5214	0	0	0	
+4.935	0.975324	1.72263	11.5286	0	0	0	
+4.936	0.975103	1.72985	11.5358	0	0	0	
+4.937	0.974881	1.73706	11.5431	0	0	0	
+4.938	0.974658	1.74426	11.5503	0	0	0	
+4.939	0.974433	1.75146	11.5575	0	0	0	
+4.94	0.974208	1.75865	11.5646	0	0	0	
+4.941	0.973982	1.76583	11.5718	0	0	0	
+4.942	0.973755	1.773	11.579	0	0	0	
+4.943	0.973527	1.78017	11.5862	0	0	0	
+4.944	0.973298	1.78733	11.5933	0	0	0	
+4.945	0.973068	1.79449	11.6005	0	0	0	
+4.946	0.972837	1.80163	11.6076	0	0	0	
+4.947	0.972605	1.80877	11.6148	0	0	0	
+4.948	0.972372	1.8159	11.6219	0	0	0	
+4.949	0.972138	1.82303	11.629	0	0	0	
+4.95	0.971903	1.83014	11.6361	0	0	0	
+4.951	0.971667	1.83725	11.6433	0	0	0	
+4.952	0.97143	1.84436	11.6504	0	0	0	
+4.953	0.971193	1.85145	11.6575	0	0	0	
+4.954	0.970954	1.85854	11.6645	0	0	0	
+4.955	0.970714	1.86562	11.6716	0	0	0	
+4.956	0.970473	1.87269	11.6787	0	0	0	
+4.957	0.970232	1.87976	11.6858	0	0	0	
+4.958	0.969989	1.88682	11.6928	0	0	0	
+4.959	0.969745	1.89387	11.6999	0	0	0	
+4.96	0.969501	1.90091	11.7069	0	0	0	
+4.961	0.969255	1.90794	11.7139	0	0	0	
+4.962	0.969009	1.91497	11.721	0	0	0	
+4.963	0.968761	1.92199	11.728	0	0	0	
+4.964	0.968513	1.929	11.735	0	0	0	
+4.965	0.968263	1.93601	11.742	0	0	0	
+4.966	0.968013	1.943	11.749	0	0	0	
+4.967	0.967761	1.94999	11.756	0	0	0	
+4.968	0.967509	1.95697	11.763	0	0	0	
+4.969	0.967256	1.96395	11.7699	0	0	0	
+4.97	0.967001	1.97091	11.7769	0	0	0	
+4.971	0.966746	1.97787	11.7839	0	0	0	
+4.972	0.96649	1.98482	11.7908	0	0	0	
+4.973	0.966233	1.99176	11.7978	0	0	0	
+4.974	0.965975	1.99869	11.8047	0	0	0	
+4.975	0.965715	2.00562	11.8116	0	0	0	
+4.976	0.965455	2.01254	11.8185	0	0	0	
+4.977	0.965194	2.01945	11.8254	0	0	0	
+4.978	0.964932	2.02635	11.8323	0	0	0	
+4.979	0.964669	2.03324	11.8392	0	0	0	
+4.98	0.964405	2.04013	11.8461	0	0	0	
+4.981	0.96414	2.04701	11.853	0	0	0	
+4.982	0.963875	2.05387	11.8599	0	0	0	
+4.983	0.963608	2.06074	11.8667	0	0	0	
+4.984	0.96334	2.06759	11.8736	0	0	0	
+4.985	0.963071	2.07443	11.8804	0	0	0	
+4.986	0.962801	2.08127	11.8873	0	0	0	
+4.987	0.962531	2.0881	11.8941	0	0	0	
+4.988	0.962259	2.09491	11.9009	0	0	0	
+4.989	0.961986	2.10173	11.9077	0	0	0	
+4.99	0.961713	2.10853	11.9145	0	0	0	
+4.991	0.961438	2.11532	11.9213	0	0	0	
+4.992	0.961163	2.12211	11.9281	0	0	0	
+4.993	0.960886	2.12888	11.9349	0	0	0	
+4.994	0.960609	2.13565	11.9417	0	0	0	
+4.995	0.960331	2.14241	11.9484	0	0	0	
+4.996	0.960051	2.14916	11.9552	0	0	0	
+4.997	0.959771	2.15591	11.9619	0	0	0	
+4.998	0.95949	2.16264	11.9686	0	0	0	
+4.999	0.959207	2.16937	11.9754	0	0	0	
+5	0.958924	2.17608	11.9821	0	0	0	
+5.001	0.95864	2.18279	11.9888	0	0	0	
+5.002	0.958355	2.18949	11.9955	0	0	0	
+5.003	0.958069	2.19618	12.0022	0	0	0	
+5.004	0.957782	2.20286	12.0089	0	0	0	
+5.005	0.957494	2.20954	12.0155	0	0	0	
+5.006	0.957205	2.2162	12.0222	0	0	0	
+5.007	0.956915	2.22286	12.0289	0	0	0	
+5.008	0.956624	2.2295	12.0355	0	0	0	
+5.009	0.956333	2.23614	12.0421	0	0	0	
+5.01	0.95604	2.24277	12.0488	0	0	0	
+5.011	0.955746	2.24939	12.0554	0	0	0	
+5.012	0.955451	2.256	12.062	0	0	0	
+5.013	0.955156	2.2626	12.0686	0	0	0	
+5.014	0.954859	2.2692	12.0752	0	0	0	
+5.015	0.954562	2.27578	12.0818	0	0	0	
+5.016	0.954263	2.28235	12.0884	0	0	0	
+5.017	0.953964	2.28892	12.0949	0	0	0	
+5.018	0.953663	2.29547	12.1015	0	0	0	
+5.019	0.953362	2.30202	12.108	0	0	0	
+5.02	0.95306	2.30856	12.1146	0	0	0	
+5.021	0.952756	2.31509	12.1211	0	0	0	
+5.022	0.952452	2.32161	12.1276	0	0	0	
+5.023	0.952147	2.32812	12.1341	0	0	0	
+5.024	0.951841	2.33462	12.1406	0	0	0	
+5.025	0.951534	2.34111	12.1471	0	0	0	
+5.026	0.951226	2.34759	12.1536	0	0	0	
+5.027	0.950917	2.35406	12.1601	0	0	0	
+5.028	0.950607	2.36053	12.1665	0	0	0	
+5.029	0.950296	2.36698	12.173	0	0	0	
+5.03	0.949984	2.37343	12.1794	0	0	0	
+5.031	0.949671	2.37986	12.1859	0	0	0	
+5.032	0.949358	2.38629	12.1923	0	0	0	
+5.033	0.949043	2.3927	12.1987	0	0	0	
+5.034	0.948727	2.39911	12.2051	0	0	0	
+5.035	0.948411	2.4055	12.2115	0	0	0	
+5.036	0.948093	2.41189	12.2179	0	0	0	
+5.037	0.947775	2.41827	12.2243	0	0	0	
+5.038	0.947455	2.42464	12.2306	0	0	0	
+5.039	0.947135	2.43099	12.237	0	0	0	
+5.04	0.946814	2.43734	12.2433	0	0	0	
+5.041	0.946492	2.44368	12.2497	0	0	0	
+5.042	0.946168	2.45001	12.256	0	0	0	
+5.043	0.945844	2.45633	12.2623	0	0	0	
+5.044	0.945519	2.46264	12.2686	0	0	0	
+5.045	0.945193	2.46894	12.2749	0	0	0	
+5.046	0.944866	2.47522	12.2812	0	0	0	
+5.047	0.944538	2.4815	12.2875	0	0	0	
+5.048	0.944209	2.48777	12.2938	0	0	0	
+5.049	0.943879	2.49403	12.3	0	0	0	
+5.05	0.943549	2.50028	12.3063	0	0	0	
+5.051	0.943217	2.50652	12.3125	0	0	0	
+5.052	0.942884	2.51275	12.3188	0	0	0	
+5.053	0.942551	2.51897	12.325	0	0	0	
+5.054	0.942216	2.52518	12.3312	0	0	0	
+5.055	0.941881	2.53138	12.3374	0	0	0	
+5.056	0.941544	2.53757	12.3436	0	0	0	
+5.057	0.941207	2.54375	12.3497	0	0	0	
+5.058	0.940869	2.54992	12.3559	0	0	0	
+5.059	0.940529	2.55608	12.3621	0	0	0	
+5.06	0.940189	2.56222	12.3682	0	0	0	
+5.061	0.939848	2.56836	12.3744	0	0	0	
+5.062	0.939506	2.57449	12.3805	0	0	0	
+5.063	0.939163	2.58061	12.3866	0	0	0	
+5.064	0.938819	2.58671	12.3927	0	0	0	
+5.065	0.938474	2.59281	12.3988	0	0	0	
+5.066	0.938128	2.5989	12.4049	0	0	0	
+5.067	0.937782	2.60497	12.411	0	0	0	
+5.068	0.937434	2.61104	12.417	0	0	0	
+5.069	0.937085	2.6171	12.4231	0	0	0	
+5.07	0.936736	2.62314	12.4291	0	0	0	
+5.071	0.936385	2.62917	12.4352	0	0	0	
+5.072	0.936034	2.6352	12.4412	0	0	0	
+5.073	0.935681	2.64121	12.4472	0	0	0	
+5.074	0.935328	2.64721	12.4532	0	0	0	
+5.075	0.934974	2.65321	12.4592	0	0	0	
+5.076	0.934619	2.65919	12.4652	0	0	0	
+5.077	0.934263	2.66516	12.4712	0	0	0	
+5.078	0.933905	2.67112	12.4771	0	0	0	
+5.079	0.933547	2.67707	12.4831	0	0	0	
+5.08	0.933189	2.68301	12.489	0	0	0	
+5.081	0.932829	2.68894	12.4949	0	0	0	
+5.082	0.932468	2.69485	12.5009	0	0	0	
+5.083	0.932106	2.70076	12.5068	0	0	0	
+5.084	0.931744	2.70666	12.5127	0	0	0	
+5.085	0.93138	2.71254	12.5185	0	0	0	
+5.086	0.931015	2.71841	12.5244	0	0	0	
+5.087	0.93065	2.72428	12.5303	0	0	0	
+5.088	0.930284	2.73013	12.5361	0	0	0	
+5.089	0.929916	2.73597	12.542	0	0	0	
+5.09	0.929548	2.7418	12.5478	0	0	0	
+5.091	0.929179	2.74762	12.5536	0	0	0	
+5.092	0.928809	2.75343	12.5594	0	0	0	
+5.093	0.928438	2.75923	12.5652	0	0	0	
+5.094	0.928066	2.76501	12.571	0	0	0	
+5.095	0.927693	2.77079	12.5768	0	0	0	
+5.096	0.927319	2.77655	12.5826	0	0	0	
+5.097	0.926944	2.78231	12.5883	0	0	0	
+5.098	0.926569	2.78805	12.594	0	0	0	
+5.099	0.926192	2.79378	12.5998	0	0	0	
+5.1	0.925815	2.7995	12.6055	0	0	0	
+5.101	0.925436	2.80521	12.6112	0	0	0	
+5.102	0.925057	2.8109	12.6169	0	0	0	
+5.103	0.924677	2.81659	12.6226	0	0	0	
+5.104	0.924295	2.82227	12.6283	0	0	0	
+5.105	0.923913	2.82793	12.6339	0	0	0	
+5.106	0.92353	2.83358	12.6396	0	0	0	
+5.107	0.923146	2.83922	12.6452	0	0	0	
+5.108	0.922761	2.84485	12.6509	0	0	0	
+5.109	0.922375	2.85047	12.6565	0	0	0	
+5.11	0.921989	2.85608	12.6621	0	0	0	
+5.111	0.921601	2.86167	12.6677	0	0	0	
+5.112	0.921212	2.86726	12.6733	0	0	0	
+5.113	0.920823	2.87283	12.6788	0	0	0	
+5.114	0.920432	2.87839	12.6844	0	0	0	
+5.115	0.920041	2.88394	12.6899	0	0	0	
+5.116	0.919649	2.88948	12.6955	0	0	0	
+5.117	0.919256	2.895	12.701	0	0	0	
+5.118	0.918861	2.90052	12.7065	0	0	0	
+5.119	0.918466	2.90602	12.712	0	0	0	
+5.12	0.91807	2.91151	12.7175	0	0	0	
+5.121	0.917674	2.91699	12.723	0	0	0	
+5.122	0.917276	2.92246	12.7285	0	0	0	
+5.123	0.916877	2.92792	12.7339	0	0	0	
+5.124	0.916477	2.93336	12.7394	0	0	0	
+5.125	0.916077	2.93879	12.7448	0	0	0	
+5.126	0.915675	2.94421	12.7502	0	0	0	
+5.127	0.915273	2.94962	12.7556	0	0	0	
+5.128	0.91487	2.95502	12.761	0	0	0	
+5.129	0.914466	2.96041	12.7664	0	0	0	
+5.13	0.91406	2.96578	12.7718	0	0	0	
+5.131	0.913654	2.97114	12.7771	0	0	0	
+5.132	0.913247	2.97649	12.7825	0	0	0	
+5.133	0.91284	2.98183	12.7878	0	0	0	
+5.134	0.912431	2.98716	12.7932	0	0	0	
+5.135	0.912021	2.99247	12.7985	0	0	0	
+5.136	0.911611	2.99778	12.8038	0	0	0	
+5.137	0.911199	3.00307	12.8091	0	0	0	
+5.138	0.910787	3.00835	12.8143	0	0	0	
+5.139	0.910373	3.01361	12.8196	0	0	0	
+5.14	0.909959	3.01887	12.8249	0	0	0	
+5.141	0.909544	3.02411	12.8301	0	0	0	
+5.142	0.909128	3.02934	12.8353	0	0	0	
+5.143	0.908711	3.03456	12.8406	0	0	0	
+5.144	0.908293	3.03976	12.8458	0	0	0	
+5.145	0.907874	3.04496	12.851	0	0	0	
+5.146	0.907454	3.05014	12.8561	0	0	0	
+5.147	0.907034	3.05531	12.8613	0	0	0	
+5.148	0.906612	3.06047	12.8665	0	0	0	
+5.149	0.90619	3.06561	12.8716	0	0	0	
+5.15	0.905767	3.07074	12.8767	0	0	0	
+5.151	0.905342	3.07586	12.8819	0	0	0	
+5.152	0.904917	3.08097	12.887	0	0	0	
+5.153	0.904491	3.08607	12.8921	0	0	0	
+5.154	0.904064	3.09115	12.8972	0	0	0	
+5.155	0.903636	3.09622	12.9022	0	0	0	
+5.156	0.903208	3.10128	12.9073	0	0	0	
+5.157	0.902778	3.10633	12.9123	0	0	0	
+5.158	0.902347	3.11136	12.9174	0	0	0	
+5.159	0.901916	3.11638	12.9224	0	0	0	
+5.16	0.901484	3.12139	12.9274	0	0	0	
+5.161	0.90105	3.12639	12.9324	0	0	0	
+5.162	0.900616	3.13137	12.9374	0	0	0	
+5.163	0.900181	3.13634	12.9423	0	0	0	
+5.164	0.899745	3.1413	12.9473	0	0	0	
+5.165	0.899308	3.14625	12.9522	0	0	0	
+5.166	0.898871	3.15118	12.9572	0	0	0	
+5.167	0.898432	3.1561	12.9621	0	0	0	
+5.168	0.897992	3.16101	12.967	0	0	0	
+5.169	0.897552	3.16591	12.9719	0	0	0	
+5.17	0.897111	3.17079	12.9768	0	0	0	
+5.171	0.896668	3.17566	12.9817	0	0	0	
+5.172	0.896225	3.18052	12.9865	0	0	0	
+5.173	0.895781	3.18537	12.9914	0	0	0	
+5.174	0.895336	3.1902	12.9962	0	0	0	
+5.175	0.89489	3.19502	13.001	0	0	0	
+5.176	0.894444	3.19982	13.0058	0	0	0	
+5.177	0.893996	3.20462	13.0106	0	0	0	
+5.178	0.893547	3.2094	13.0154	0	0	0	
+5.179	0.893098	3.21417	13.0202	0	0	0	
+5.18	0.892648	3.21892	13.0249	0	0	0	
+5.181	0.892196	3.22367	13.0297	0	0	0	
+5.182	0.891744	3.2284	13.0344	0	0	0	
+5.183	0.891291	3.23311	13.0391	0	0	0	
+5.184	0.890838	3.23782	13.0438	0	0	0	
+5.185	0.890383	3.24251	13.0485	0	0	0	
+5.186	0.889927	3.24719	13.0532	0	0	0	
+5.187	0.889471	3.25185	13.0579	0	0	0	
+5.188	0.889013	3.2565	13.0625	0	0	0	
+5.189	0.888555	3.26114	13.0671	0	0	0	
+5.19	0.888096	3.26577	13.0718	0	0	0	
+5.191	0.887635	3.27038	13.0764	0	0	0	
+5.192	0.887174	3.27498	13.081	0	0	0	
+5.193	0.886713	3.27957	13.0856	0	0	0	
+5.194	0.88625	3.28414	13.0901	0	0	0	
+5.195	0.885786	3.2887	13.0947	0	0	0	
+5.196	0.885322	3.29325	13.0992	0	0	0	
+5.197	0.884856	3.29778	13.1038	0	0	0	
+5.198	0.88439	3.3023	13.1083	0	0	0	
+5.199	0.883923	3.30681	13.1128	0	0	0	
+5.2	0.883455	3.31131	13.1173	0	0	0	
+5.201	0.882986	3.31579	13.1218	0	0	0	
+5.202	0.882516	3.32026	13.1263	0	0	0	
+5.203	0.882045	3.32471	13.1307	0	0	0	
+5.204	0.881574	3.32915	13.1352	0	0	0	
+5.205	0.881101	3.33358	13.1396	0	0	0	
+5.206	0.880628	3.33799	13.144	0	0	0	
+5.207	0.880153	3.3424	13.1484	0	0	0	
+5.208	0.879678	3.34678	13.1528	0	0	0	
+5.209	0.879202	3.35116	13.1572	0	0	0	
+5.21	0.878725	3.35552	13.1615	0	0	0	
+5.211	0.878248	3.35987	13.1659	0	0	0	
+5.212	0.877769	3.3642	13.1702	0	0	0	
+5.213	0.877289	3.36852	13.1745	0	0	0	
+5.214	0.876809	3.37283	13.1788	0	0	0	
+5.215	0.876328	3.37712	13.1831	0	0	0	
+5.216	0.875846	3.3814	13.1874	0	0	0	
+5.217	0.875363	3.38567	13.1917	0	0	0	
+5.218	0.874879	3.38992	13.1959	0	0	0	
+5.219	0.874394	3.39416	13.2002	0	0	0	
+5.22	0.873908	3.39839	13.2044	0	0	0	
+5.221	0.873422	3.4026	13.2086	0	0	0	
+5.222	0.872934	3.4068	13.2128	0	0	0	
+5.223	0.872446	3.41099	13.217	0	0	0	
+5.224	0.871957	3.41516	13.2212	0	0	0	
+5.225	0.871467	3.41932	13.2253	0	0	0	
+5.226	0.870976	3.42346	13.2295	0	0	0	
+5.227	0.870484	3.42759	13.2336	0	0	0	
+5.228	0.869992	3.43171	13.2377	0	0	0	
+5.229	0.869498	3.43581	13.2418	0	0	0	
+5.23	0.869004	3.4399	13.2459	0	0	0	
+5.231	0.868508	3.44398	13.25	0	0	0	
+5.232	0.868012	3.44804	13.254	0	0	0	
+5.233	0.867515	3.45209	13.2581	0	0	0	
+5.234	0.867018	3.45612	13.2621	0	0	0	
+5.235	0.866519	3.46014	13.2661	0	0	0	
+5.236	0.866019	3.46415	13.2702	0	0	0	
+5.237	0.865519	3.46814	13.2741	0	0	0	
+5.238	0.865018	3.47212	13.2781	0	0	0	
+5.239	0.864515	3.47609	13.2821	0	0	0	
+5.24	0.864012	3.48004	13.286	0	0	0	
+5.241	0.863508	3.48398	13.29	0	0	0	
+5.242	0.863004	3.4879	13.2939	0	0	0	
+5.243	0.862498	3.49181	13.2978	0	0	0	
+5.244	0.861992	3.4957	13.3017	0	0	0	
+5.245	0.861484	3.49959	13.3056	0	0	0	
+5.246	0.860976	3.50345	13.3095	0	0	0	
+5.247	0.860467	3.50731	13.3133	0	0	0	
+5.248	0.859957	3.51115	13.3171	0	0	0	
+5.249	0.859446	3.51497	13.321	0	0	0	
+5.25	0.858934	3.51878	13.3248	0	0	0	
+5.251	0.858422	3.52258	13.3286	0	0	0	
+5.252	0.857909	3.52636	13.3324	0	0	0	
+5.253	0.857394	3.53013	13.3361	0	0	0	
+5.254	0.856879	3.53389	13.3399	0	0	0	
+5.255	0.856363	3.53763	13.3436	0	0	0	
+5.256	0.855847	3.54135	13.3474	0	0	0	
+5.257	0.855329	3.54507	13.3511	0	0	0	
+5.258	0.85481	3.54877	13.3548	0	0	0	
+5.259	0.854291	3.55245	13.3584	0	0	0	
+5.26	0.853771	3.55612	13.3621	0	0	0	
+5.261	0.85325	3.55978	13.3658	0	0	0	
+5.262	0.852728	3.56342	13.3694	0	0	0	
+5.263	0.852205	3.56704	13.373	0	0	0	
+5.264	0.851681	3.57066	13.3767	0	0	0	
+5.265	0.851157	3.57426	13.3803	0	0	0	
+5.266	0.850632	3.57784	13.3838	0	0	0	
+5.267	0.850105	3.58141	13.3874	0	0	0	
+5.268	0.849578	3.58497	13.391	0	0	0	
+5.269	0.84905	3.58851	13.3945	0	0	0	
+5.27	0.848522	3.59203	13.398	0	0	0	
+5.271	0.847992	3.59555	13.4015	0	0	0	
+5.272	0.847462	3.59904	13.405	0	0	0	
+5.273	0.84693	3.60253	13.4085	0	0	0	
+5.274	0.846398	3.606	13.412	0	0	0	
+5.275	0.845865	3.60945	13.4155	0	0	0	
+5.276	0.845331	3.61289	13.4189	0	0	0	
+5.277	0.844797	3.61632	13.4223	0	0	0	
+5.278	0.844261	3.61973	13.4257	0	0	0	
+5.279	0.843725	3.62313	13.4291	0	0	0	
+5.28	0.843188	3.62651	13.4325	0	0	0	
+5.281	0.84265	3.62988	13.4359	0	0	0	
+5.282	0.842111	3.63323	13.4392	0	0	0	
+5.283	0.841571	3.63657	13.4426	0	0	0	
+5.284	0.841031	3.6399	13.4459	0	0	0	
+5.285	0.840489	3.64321	13.4492	0	0	0	
+5.286	0.839947	3.6465	13.4525	0	0	0	
+5.287	0.839404	3.64978	13.4558	0	0	0	
+5.288	0.83886	3.65305	13.459	0	0	0	
+5.289	0.838315	3.6563	13.4623	0	0	0	
+5.29	0.837769	3.65954	13.4655	0	0	0	
+5.291	0.837223	3.66276	13.4688	0	0	0	
+5.292	0.836676	3.66597	13.472	0	0	0	
+5.293	0.836128	3.66916	13.4752	0	0	0	
+5.294	0.835579	3.67234	13.4783	0	0	0	
+5.295	0.835029	3.6755	13.4815	0	0	0	
+5.296	0.834478	3.67865	13.4847	0	0	0	
+5.297	0.833927	3.68179	13.4878	0	0	0	
+5.298	0.833375	3.68491	13.4909	0	0	0	
+5.299	0.832821	3.68801	13.494	0	0	0	
+5.3	0.832267	3.6911	13.4971	0	0	0	
+5.301	0.831713	3.69418	13.5002	0	0	0	
+5.302	0.831157	3.69724	13.5032	0	0	0	
+5.303	0.830601	3.70028	13.5063	0	0	0	
+5.304	0.830043	3.70331	13.5093	0	0	0	
+5.305	0.829485	3.70633	13.5123	0	0	0	
+5.306	0.828926	3.70933	13.5153	0	0	0	
+5.307	0.828366	3.71232	13.5183	0	0	0	
+5.308	0.827806	3.71529	13.5213	0	0	0	
+5.309	0.827244	3.71825	13.5242	0	0	0	
+5.31	0.826682	3.72119	13.5272	0	0	0	
+5.311	0.826119	3.72412	13.5301	0	0	0	
+5.312	0.825555	3.72703	13.533	0	0	0	
+5.313	0.82499	3.72992	13.5359	0	0	0	
+5.314	0.824425	3.73281	13.5388	0	0	0	
+5.315	0.823859	3.73567	13.5417	0	0	0	
+5.316	0.823291	3.73853	13.5445	0	0	0	
+5.317	0.822723	3.74136	13.5474	0	0	0	
+5.318	0.822154	3.74419	13.5502	0	0	0	
+5.319	0.821585	3.74699	13.553	0	0	0	
+5.32	0.821014	3.74979	13.5558	0	0	0	
+5.321	0.820443	3.75256	13.5586	0	0	0	
+5.322	0.819871	3.75533	13.5613	0	0	0	
+5.323	0.819298	3.75807	13.5641	0	0	0	
+5.324	0.818724	3.76081	13.5668	0	0	0	
+5.325	0.818149	3.76352	13.5695	0	0	0	
+5.326	0.817574	3.76623	13.5722	0	0	0	
+5.327	0.816998	3.76891	13.5749	0	0	0	
+5.328	0.816421	3.77159	13.5776	0	0	0	
+5.329	0.815843	3.77424	13.5802	0	0	0	
+5.33	0.815264	3.77689	13.5829	0	0	0	
+5.331	0.814685	3.77951	13.5855	0	0	0	
+5.332	0.814104	3.78212	13.5881	0	0	0	
+5.333	0.813523	3.78472	13.5907	0	0	0	
+5.334	0.812941	3.7873	13.5933	0	0	0	
+5.335	0.812359	3.78987	13.5959	0	0	0	
+5.336	0.811775	3.79242	13.5984	0	0	0	
+5.337	0.811191	3.79496	13.601	0	0	0	
+5.338	0.810605	3.79748	13.6035	0	0	0	
+5.339	0.810019	3.79998	13.606	0	0	0	
+5.34	0.809433	3.80247	13.6085	0	0	0	
+5.341	0.808845	3.80495	13.6109	0	0	0	
+5.342	0.808257	3.80741	13.6134	0	0	0	
+5.343	0.807667	3.80985	13.6159	0	0	0	
+5.344	0.807077	3.81228	13.6183	0	0	0	
+5.345	0.806486	3.8147	13.6207	0	0	0	
+5.346	0.805895	3.8171	13.6231	0	0	0	
+5.347	0.805302	3.81948	13.6255	0	0	0	
+5.348	0.804709	3.82185	13.6278	0	0	0	
+5.349	0.804115	3.8242	13.6302	0	0	0	
+5.35	0.80352	3.82654	13.6325	0	0	0	
+5.351	0.802924	3.82886	13.6349	0	0	0	
+5.352	0.802328	3.83117	13.6372	0	0	0	
+5.353	0.801731	3.83346	13.6395	0	0	0	
+5.354	0.801133	3.83574	13.6417	0	0	0	
+5.355	0.800534	3.838	13.644	0	0	0	
+5.356	0.799934	3.84025	13.6462	0	0	0	
+5.357	0.799334	3.84248	13.6485	0	0	0	
+5.358	0.798732	3.84469	13.6507	0	0	0	
+5.359	0.79813	3.84689	13.6529	0	0	0	
+5.36	0.797527	3.84908	13.6551	0	0	0	
+5.361	0.796924	3.85125	13.6572	0	0	0	
+5.362	0.796319	3.8534	13.6594	0	0	0	
+5.363	0.795714	3.85554	13.6615	0	0	0	
+5.364	0.795108	3.85766	13.6637	0	0	0	
+5.365	0.794501	3.85977	13.6658	0	0	0	
+5.366	0.793893	3.86186	13.6679	0	0	0	
+5.367	0.793285	3.86394	13.6699	0	0	0	
+5.368	0.792676	3.866	13.672	0	0	0	
+5.369	0.792066	3.86804	13.674	0	0	0	
+5.37	0.791455	3.87007	13.6761	0	0	0	
+5.371	0.790843	3.87209	13.6781	0	0	0	
+5.372	0.790231	3.87409	13.6801	0	0	0	
+5.373	0.789617	3.87607	13.6821	0	0	0	
+5.374	0.789003	3.87804	13.684	0	0	0	
+5.375	0.788389	3.87999	13.686	0	0	0	
+5.376	0.787773	3.88193	13.6879	0	0	0	
+5.377	0.787157	3.88385	13.6899	0	0	0	
+5.378	0.78654	3.88576	13.6918	0	0	0	
+5.379	0.785922	3.88765	13.6936	0	0	0	
+5.38	0.785303	3.88952	13.6955	0	0	0	
+5.381	0.784683	3.89138	13.6974	0	0	0	
+5.382	0.784063	3.89323	13.6992	0	0	0	
+5.383	0.783442	3.89505	13.7011	0	0	0	
+5.384	0.78282	3.89687	13.7029	0	0	0	
+5.385	0.782198	3.89866	13.7047	0	0	0	
+5.386	0.781574	3.90044	13.7064	0	0	0	
+5.387	0.78095	3.90221	13.7082	0	0	0	
+5.388	0.780325	3.90396	13.71	0	0	0	
+5.389	0.779699	3.9057	13.7117	0	0	0	
+5.39	0.779073	3.90741	13.7134	0	0	0	
+5.391	0.778445	3.90912	13.7151	0	0	0	
+5.392	0.777817	3.91081	13.7168	0	0	0	
+5.393	0.777188	3.91248	13.7185	0	0	0	
+5.394	0.776559	3.91413	13.7201	0	0	0	
+5.395	0.775928	3.91578	13.7218	0	0	0	
+5.396	0.775297	3.9174	13.7234	0	0	0	
+5.397	0.774665	3.91901	13.725	0	0	0	
+5.398	0.774032	3.9206	13.7266	0	0	0	
+5.399	0.773399	3.92218	13.7282	0	0	0	
+5.4	0.772764	3.92374	13.7297	0	0	0	
+5.401	0.772129	3.92529	13.7313	0	0	0	
+5.402	0.771494	3.92682	13.7328	0	0	0	
+5.403	0.770857	3.92834	13.7343	0	0	0	
+5.404	0.77022	3.92984	13.7358	0	0	0	
+5.405	0.769581	3.93132	13.7373	0	0	0	
+5.406	0.768942	3.93279	13.7388	0	0	0	
+5.407	0.768303	3.93424	13.7402	0	0	0	
+5.408	0.767662	3.93568	13.7417	0	0	0	
+5.409	0.767021	3.9371	13.7431	0	0	0	
+5.41	0.766379	3.93851	13.7445	0	0	0	
+5.411	0.765736	3.9399	13.7459	0	0	0	
+5.412	0.765093	3.94127	13.7473	0	0	0	
+5.413	0.764448	3.94263	13.7486	0	0	0	
+5.414	0.763803	3.94397	13.75	0	0	0	
+5.415	0.763158	3.9453	13.7513	0	0	0	
+5.416	0.762511	3.94661	13.7526	0	0	0	
+5.417	0.761864	3.9479	13.7539	0	0	0	
+5.418	0.761215	3.94918	13.7552	0	0	0	
+5.419	0.760567	3.95044	13.7564	0	0	0	
+5.42	0.759917	3.95169	13.7577	0	0	0	
+5.421	0.759267	3.95292	13.7589	0	0	0	
+5.422	0.758615	3.95414	13.7601	0	0	0	
+5.423	0.757963	3.95534	13.7613	0	0	0	
+5.424	0.757311	3.95652	13.7625	0	0	0	
+5.425	0.756657	3.95769	13.7637	0	0	0	
+5.426	0.756003	3.95884	13.7648	0	0	0	
+5.427	0.755348	3.95998	13.766	0	0	0	
+5.428	0.754693	3.9611	13.7671	0	0	0	
+5.429	0.754036	3.96221	13.7682	0	0	0	
+5.43	0.753379	3.9633	13.7693	0	0	0	
+5.431	0.752721	3.96437	13.7704	0	0	0	
+5.432	0.752062	3.96543	13.7714	0	0	0	
+5.433	0.751403	3.96647	13.7725	0	0	0	
+5.434	0.750742	3.96749	13.7735	0	0	0	
+5.435	0.750082	3.9685	13.7745	0	0	0	
+5.436	0.74942	3.9695	13.7755	0	0	0	
+5.437	0.748757	3.97048	13.7765	0	0	0	
+5.438	0.748094	3.97144	13.7774	0	0	0	
+5.439	0.74743	3.97238	13.7784	0	0	0	
+5.44	0.746765	3.97331	13.7793	0	0	0	
+5.441	0.7461	3.97423	13.7802	0	0	0	
+5.442	0.745434	3.97513	13.7811	0	0	0	
+5.443	0.744767	3.97601	13.782	0	0	0	
+5.444	0.744099	3.97688	13.7829	0	0	0	
+5.445	0.743431	3.97773	13.7837	0	0	0	
+5.446	0.742761	3.97856	13.7846	0	0	0	
+5.447	0.742092	3.97938	13.7854	0	0	0	
+5.448	0.741421	3.98019	13.7862	0	0	0	
+5.449	0.740749	3.98097	13.787	0	0	0	
+5.45	0.740077	3.98175	13.7877	0	0	0	
+5.451	0.739404	3.9825	13.7885	0	0	0	
+5.452	0.738731	3.98324	13.7892	0	0	0	
+5.453	0.738056	3.98396	13.79	0	0	0	
+5.454	0.737381	3.98467	13.7907	0	0	0	
+5.455	0.736705	3.98536	13.7914	0	0	0	
+5.456	0.736029	3.98604	13.792	0	0	0	
+5.457	0.735352	3.9867	13.7927	0	0	0	
+5.458	0.734674	3.98734	13.7933	0	0	0	
+5.459	0.733995	3.98797	13.794	0	0	0	
+5.46	0.733315	3.98858	13.7946	0	0	0	
+5.461	0.732635	3.98918	13.7952	0	0	0	
+5.462	0.731954	3.98976	13.7958	0	0	0	
+5.463	0.731272	3.99032	13.7963	0	0	0	
+5.464	0.73059	3.99087	13.7969	0	0	0	
+5.465	0.729907	3.9914	13.7974	0	0	0	
+5.466	0.729223	3.99192	13.7979	0	0	0	
+5.467	0.728538	3.99242	13.7984	0	0	0	
+5.468	0.727853	3.9929	13.7989	0	0	0	
+5.469	0.727167	3.99337	13.7994	0	0	0	
+5.47	0.72648	3.99382	13.7998	0	0	0	
+5.471	0.725792	3.99426	13.8003	0	0	0	
+5.472	0.725104	3.99468	13.8007	0	0	0	
+5.473	0.724415	3.99509	13.8011	0	0	0	
+5.474	0.723725	3.99547	13.8015	0	0	0	
+5.475	0.723035	3.99585	13.8018	0	0	0	
+5.476	0.722344	3.9962	13.8022	0	0	0	
+5.477	0.721652	3.99654	13.8025	0	0	0	
+5.478	0.720959	3.99687	13.8029	0	0	0	
+5.479	0.720266	3.99718	13.8032	0	0	0	
+5.48	0.719572	3.99747	13.8035	0	0	0	
+5.481	0.718877	3.99775	13.8037	0	0	0	
+5.482	0.718181	3.99801	13.804	0	0	0	
+5.483	0.717485	3.99825	13.8043	0	0	0	
+5.484	0.716788	3.99848	13.8045	0	0	0	
+5.485	0.716091	3.99869	13.8047	0	0	0	
+5.486	0.715392	3.99889	13.8049	0	0	0	
+5.487	0.714693	3.99907	13.8051	0	0	0	
+5.488	0.713993	3.99923	13.8052	0	0	0	
+5.489	0.713293	3.99938	13.8054	0	0	0	
+5.49	0.712592	3.99951	13.8055	0	0	0	
+5.491	0.71189	3.99963	13.8056	0	0	0	
+5.492	0.711187	3.99973	13.8057	0	0	0	
+5.493	0.710484	3.99982	13.8058	0	0	0	
+5.494	0.70978	3.99989	13.8059	0	0	0	
+5.495	0.709075	3.99994	13.8059	0	0	0	
+5.496	0.708369	3.99997	13.806	0	0	0	
+5.497	0.707663	4	13.806	0	0	0	
+5.498	0.706956	4	13.806	0	0	0	
+5.499	0.706249	3.99999	13.806	0	0	0	
+5.5	0.70554	3.99996	13.806	0	0	0	
+5.501	0.704831	3.99992	13.8059	0	0	0	
+5.502	0.704122	3.99986	13.8059	0	0	0	
+5.503	0.703411	3.99978	13.8058	0	0	0	
+5.504	0.7027	3.99969	13.8057	0	0	0	
+5.505	0.701988	3.99958	13.8056	0	0	0	
+5.506	0.701276	3.99946	13.8055	0	0	0	
+5.507	0.700562	3.99932	13.8053	0	0	0	
+5.508	0.699848	3.99917	13.8052	0	0	0	
+5.509	0.699134	3.99899	13.805	0	0	0	
+5.51	0.698418	3.99881	13.8048	0	0	0	
+5.511	0.697702	3.9986	13.8046	0	0	0	
+5.512	0.696986	3.99838	13.8044	0	0	0	
+5.513	0.696268	3.99815	13.8041	0	0	0	
+5.514	0.69555	3.9979	13.8039	0	0	0	
+5.515	0.694831	3.99763	13.8036	0	0	0	
+5.516	0.694112	3.99735	13.8033	0	0	0	
+5.517	0.693392	3.99705	13.803	0	0	0	
+5.518	0.692671	3.99673	13.8027	0	0	0	
+5.519	0.691949	3.9964	13.8024	0	0	0	
+5.52	0.691227	3.99605	13.8021	0	0	0	
+5.521	0.690504	3.99569	13.8017	0	0	0	
+5.522	0.68978	3.99531	13.8013	0	0	0	
+5.523	0.689056	3.99492	13.8009	0	0	0	
+5.524	0.688331	3.9945	13.8005	0	0	0	
+5.525	0.687605	3.99408	13.8001	0	0	0	
+5.526	0.686879	3.99363	13.7996	0	0	0	
+5.527	0.686151	3.99317	13.7992	0	0	0	
+5.528	0.685424	3.9927	13.7987	0	0	0	
+5.529	0.684695	3.99221	13.7982	0	0	0	
+5.53	0.683966	3.9917	13.7977	0	0	0	
+5.531	0.683236	3.99118	13.7972	0	0	0	
+5.532	0.682506	3.99064	13.7966	0	0	0	
+5.533	0.681774	3.99008	13.7961	0	0	0	
+5.534	0.681042	3.98951	13.7955	0	0	0	
+5.535	0.68031	3.98893	13.7949	0	0	0	
+5.536	0.679577	3.98832	13.7943	0	0	0	
+5.537	0.678843	3.98771	13.7937	0	0	0	
+5.538	0.678108	3.98707	13.7931	0	0	0	
+5.539	0.677373	3.98642	13.7924	0	0	0	
+5.54	0.676637	3.98575	13.7918	0	0	0	
+5.541	0.6759	3.98507	13.7911	0	0	0	
+5.542	0.675163	3.98437	13.7904	0	0	0	
+5.543	0.674425	3.98366	13.7897	0	0	0	
+5.544	0.673686	3.98293	13.7889	0	0	0	
+5.545	0.672947	3.98218	13.7882	0	0	0	
+5.546	0.672207	3.98142	13.7874	0	0	0	
+5.547	0.671466	3.98064	13.7866	0	0	0	
+5.548	0.670725	3.97985	13.7858	0	0	0	
+5.549	0.669983	3.97904	13.785	0	0	0	
+5.55	0.66924	3.97821	13.7842	0	0	0	
+5.551	0.668496	3.97737	13.7834	0	0	0	
+5.552	0.667752	3.97651	13.7825	0	0	0	
+5.553	0.667008	3.97564	13.7816	0	0	0	
+5.554	0.666262	3.97475	13.7807	0	0	0	
+5.555	0.665516	3.97384	13.7798	0	0	0	
+5.556	0.66477	3.97292	13.7789	0	0	0	
+5.557	0.664022	3.97198	13.778	0	0	0	
+5.558	0.663274	3.97103	13.777	0	0	0	
+5.559	0.662525	3.97006	13.7761	0	0	0	
+5.56	0.661776	3.96908	13.7751	0	0	0	
+5.561	0.661026	3.96808	13.7741	0	0	0	
+5.562	0.660275	3.96706	13.7731	0	0	0	
+5.563	0.659524	3.96603	13.772	0	0	0	
+5.564	0.658772	3.96498	13.771	0	0	0	
+5.565	0.658019	3.96391	13.7699	0	0	0	
+5.566	0.657266	3.96283	13.7688	0	0	0	
+5.567	0.656512	3.96174	13.7677	0	0	0	
+5.568	0.655757	3.96063	13.7666	0	0	0	
+5.569	0.655002	3.9595	13.7655	0	0	0	
+5.57	0.654246	3.95835	13.7644	0	0	0	
+5.571	0.653489	3.9572	13.7632	0	0	0	
+5.572	0.652732	3.95602	13.762	0	0	0	
+5.573	0.651974	3.95483	13.7608	0	0	0	
+5.574	0.651216	3.95362	13.7596	0	0	0	
+5.575	0.650457	3.9524	13.7584	0	0	0	
+5.576	0.649697	3.95116	13.7572	0	0	0	
+5.577	0.648936	3.94991	13.7559	0	0	0	
+5.578	0.648175	3.94864	13.7546	0	0	0	
+5.579	0.647413	3.94735	13.7534	0	0	0	
+5.58	0.646651	3.94605	13.7521	0	0	0	
+5.581	0.645888	3.94473	13.7507	0	0	0	
+5.582	0.645124	3.9434	13.7494	0	0	0	
+5.583	0.644359	3.94205	13.7481	0	0	0	
+5.584	0.643594	3.94069	13.7467	0	0	0	
+5.585	0.642829	3.93931	13.7453	0	0	0	
+5.586	0.642062	3.93791	13.7439	0	0	0	
+5.587	0.641295	3.9365	13.7425	0	0	0	
+5.588	0.640528	3.93507	13.7411	0	0	0	
+5.589	0.639759	3.93363	13.7396	0	0	0	
+5.59	0.638991	3.93217	13.7382	0	0	0	
+5.591	0.638221	3.93069	13.7367	0	0	0	
+5.592	0.637451	3.9292	13.7352	0	0	0	
+5.593	0.63668	3.92769	13.7337	0	0	0	
+5.594	0.635909	3.92617	13.7322	0	0	0	
+5.595	0.635137	3.92464	13.7306	0	0	0	
+5.596	0.634364	3.92308	13.7291	0	0	0	
+5.597	0.63359	3.92151	13.7275	0	0	0	
+5.598	0.632817	3.91993	13.7259	0	0	0	
+5.599	0.632042	3.91833	13.7243	0	0	0	
+5.6	0.631267	3.91671	13.7227	0	0	0	
+5.601	0.630491	3.91508	13.7211	0	0	0	
+5.602	0.629714	3.91343	13.7194	0	0	0	
+5.603	0.628937	3.91177	13.7178	0	0	0	
+5.604	0.628159	3.91009	13.7161	0	0	0	
+5.605	0.627381	3.9084	13.7144	0	0	0	
+5.606	0.626602	3.90668	13.7127	0	0	0	
+5.607	0.625822	3.90496	13.711	0	0	0	
+5.608	0.625042	3.90322	13.7092	0	0	0	
+5.609	0.624261	3.90146	13.7075	0	0	0	
+5.61	0.62348	3.89969	13.7057	0	0	0	
+5.611	0.622697	3.8979	13.7039	0	0	0	
+5.612	0.621915	3.8961	13.7021	0	0	0	
+5.613	0.621131	3.89428	13.7003	0	0	0	
+5.614	0.620347	3.89244	13.6984	0	0	0	
+5.615	0.619563	3.89059	13.6966	0	0	0	
+5.616	0.618777	3.88873	13.6947	0	0	0	
+5.617	0.617991	3.88684	13.6928	0	0	0	
+5.618	0.617205	3.88495	13.6909	0	0	0	
+5.619	0.616418	3.88303	13.689	0	0	0	
+5.62	0.61563	3.88111	13.6871	0	0	0	
+5.621	0.614842	3.87916	13.6852	0	0	0	
+5.622	0.614053	3.8772	13.6832	0	0	0	
+5.623	0.613263	3.87523	13.6812	0	0	0	
+5.624	0.612473	3.87324	13.6792	0	0	0	
+5.625	0.611682	3.87123	13.6772	0	0	0	
+5.626	0.610891	3.86921	13.6752	0	0	0	
+5.627	0.610099	3.86717	13.6732	0	0	0	
+5.628	0.609306	3.86512	13.6711	0	0	0	
+5.629	0.608513	3.86305	13.6691	0	0	0	
+5.63	0.607719	3.86097	13.667	0	0	0	
+5.631	0.606925	3.85887	13.6649	0	0	0	
+5.632	0.60613	3.85676	13.6628	0	0	0	
+5.633	0.605334	3.85463	13.6606	0	0	0	
+5.634	0.604538	3.85248	13.6585	0	0	0	
+5.635	0.603741	3.85032	13.6563	0	0	0	
+5.636	0.602943	3.84815	13.6541	0	0	0	
+5.637	0.602145	3.84596	13.652	0	0	0	
+5.638	0.601347	3.84375	13.6498	0	0	0	
+5.639	0.600547	3.84153	13.6475	0	0	0	
+5.64	0.599747	3.83929	13.6453	0	0	0	
+5.641	0.598947	3.83704	13.643	0	0	0	
+5.642	0.598146	3.83477	13.6408	0	0	0	
+5.643	0.597344	3.83249	13.6385	0	0	0	
+5.644	0.596542	3.83019	13.6362	0	0	0	
+5.645	0.595739	3.82788	13.6339	0	0	0	
+5.646	0.594935	3.82555	13.6315	0	0	0	
+5.647	0.594131	3.8232	13.6292	0	0	0	
+5.648	0.593327	3.82084	13.6268	0	0	0	
+5.649	0.592521	3.81847	13.6245	0	0	0	
+5.65	0.591716	3.81608	13.6221	0	0	0	
+5.651	0.590909	3.81367	13.6197	0	0	0	
+5.652	0.590102	3.81125	13.6173	0	0	0	
+5.653	0.589294	3.80881	13.6148	0	0	0	
+5.654	0.588486	3.80636	13.6124	0	0	0	
+5.655	0.587677	3.8039	13.6099	0	0	0	
+5.656	0.586868	3.80141	13.6074	0	0	0	
+5.657	0.586058	3.79892	13.6049	0	0	0	
+5.658	0.585248	3.79641	13.6024	0	0	0	
+5.659	0.584436	3.79388	13.5999	0	0	0	
+5.66	0.583625	3.79134	13.5973	0	0	0	
+5.661	0.582812	3.78878	13.5948	0	0	0	
+5.662	0.581999	3.78621	13.5922	0	0	0	
+5.663	0.581186	3.78362	13.5896	0	0	0	
+5.664	0.580372	3.78101	13.587	0	0	0	
+5.665	0.579557	3.7784	13.5844	0	0	0	
+5.666	0.578742	3.77576	13.5818	0	0	0	
+5.667	0.577926	3.77311	13.5791	0	0	0	
+5.668	0.57711	3.77045	13.5765	0	0	0	
+5.669	0.576293	3.76777	13.5738	0	0	0	
+5.67	0.575475	3.76508	13.5711	0	0	0	
+5.671	0.574657	3.76237	13.5684	0	0	0	
+5.672	0.573839	3.75965	13.5656	0	0	0	
+5.673	0.573019	3.75691	13.5629	0	0	0	
+5.674	0.5722	3.75415	13.5602	0	0	0	
+5.675	0.571379	3.75138	13.5574	0	0	0	
+5.676	0.570558	3.7486	13.5546	0	0	0	
+5.677	0.569737	3.7458	13.5518	0	0	0	
+5.678	0.568914	3.74299	13.549	0	0	0	
+5.679	0.568092	3.74016	13.5462	0	0	0	
+5.68	0.567269	3.73731	13.5433	0	0	0	
+5.681	0.566445	3.73446	13.5405	0	0	0	
+5.682	0.56562	3.73158	13.5376	0	0	0	
+5.683	0.564795	3.72869	13.5347	0	0	0	
+5.684	0.56397	3.72579	13.5318	0	0	0	
+5.685	0.563144	3.72287	13.5289	0	0	0	
+5.686	0.562317	3.71994	13.5259	0	0	0	
+5.687	0.56149	3.71699	13.523	0	0	0	
+5.688	0.560662	3.71403	13.52	0	0	0	
+5.689	0.559834	3.71105	13.517	0	0	0	
+5.69	0.559005	3.70806	13.5141	0	0	0	
+5.691	0.558176	3.70505	13.511	0	0	0	
+5.692	0.557346	3.70203	13.508	0	0	0	
+5.693	0.556515	3.69899	13.505	0	0	0	
+5.694	0.555684	3.69594	13.5019	0	0	0	
+5.695	0.554852	3.69287	13.4989	0	0	0	
+5.696	0.55402	3.68979	13.4958	0	0	0	
+5.697	0.553187	3.68669	13.4927	0	0	0	
+5.698	0.552354	3.68358	13.4896	0	0	0	
+5.699	0.55152	3.68045	13.4865	0	0	0	
+5.7	0.550686	3.67731	13.4833	0	0	0	
+5.701	0.549851	3.67416	13.4802	0	0	0	
+5.702	0.549015	3.67099	13.477	0	0	0	
+5.703	0.548179	3.6678	13.4738	0	0	0	
+5.704	0.547342	3.6646	13.4706	0	0	0	
+5.705	0.546505	3.66139	13.4674	0	0	0	
+5.706	0.545667	3.65816	13.4642	0	0	0	
+5.707	0.544829	3.65492	13.4609	0	0	0	
+5.708	0.54399	3.65166	13.4577	0	0	0	
+5.709	0.543151	3.64839	13.4544	0	0	0	
+5.71	0.542311	3.6451	13.4511	0	0	0	
+5.711	0.541471	3.6418	13.4478	0	0	0	
+5.712	0.54063	3.63848	13.4445	0	0	0	
+5.713	0.539788	3.63515	13.4412	0	0	0	
+5.714	0.538946	3.63181	13.4378	0	0	0	
+5.715	0.538103	3.62845	13.4344	0	0	0	
+5.716	0.53726	3.62507	13.4311	0	0	0	
+5.717	0.536417	3.62168	13.4277	0	0	0	
+5.718	0.535572	3.61828	13.4243	0	0	0	
+5.719	0.534728	3.61486	13.4209	0	0	0	
+5.72	0.533882	3.61143	13.4174	0	0	0	
+5.721	0.533036	3.60798	13.414	0	0	0	
+5.722	0.53219	3.60452	13.4105	0	0	0	
+5.723	0.531343	3.60105	13.407	0	0	0	
+5.724	0.530496	3.59756	13.4036	0	0	0	
+5.725	0.529648	3.59405	13.4001	0	0	0	
+5.726	0.528799	3.59053	13.3965	0	0	0	
+5.727	0.52795	3.587	13.393	0	0	0	
+5.728	0.527101	3.58345	13.3895	0	0	0	
+5.729	0.526251	3.57989	13.3859	0	0	0	
+5.73	0.5254	3.57632	13.3823	0	0	0	
+5.731	0.524549	3.57273	13.3787	0	0	0	
+5.732	0.523697	3.56912	13.3751	0	0	0	
+5.733	0.522845	3.5655	13.3715	0	0	0	
+5.734	0.521993	3.56187	13.3679	0	0	0	
+5.735	0.521139	3.55822	13.3642	0	0	0	
+5.736	0.520286	3.55456	13.3606	0	0	0	
+5.737	0.519431	3.55088	13.3569	0	0	0	
+5.738	0.518577	3.54719	13.3532	0	0	0	
+5.739	0.517721	3.54349	13.3495	0	0	0	
+5.74	0.516865	3.53977	13.3458	0	0	0	
+5.741	0.516009	3.53604	13.342	0	0	0	
+5.742	0.515152	3.53229	13.3383	0	0	0	
+5.743	0.514295	3.52853	13.3345	0	0	0	
+5.744	0.513437	3.52475	13.3308	0	0	0	
+5.745	0.512579	3.52097	13.327	0	0	0	
+5.746	0.51172	3.51716	13.3232	0	0	0	
+5.747	0.51086	3.51334	13.3193	0	0	0	
+5.748	0.51	3.50951	13.3155	0	0	0	
+5.749	0.50914	3.50567	13.3117	0	0	0	
+5.75	0.508279	3.50181	13.3078	0	0	0	
+5.751	0.507418	3.49794	13.3039	0	0	0	
+5.752	0.506556	3.49405	13.3	0	0	0	
+5.753	0.505693	3.49015	13.2961	0	0	0	
+5.754	0.50483	3.48623	13.2922	0	0	0	
+5.755	0.503967	3.4823	13.2883	0	0	0	
+5.756	0.503103	3.47836	13.2844	0	0	0	
+5.757	0.502238	3.4744	13.2804	0	0	0	
+5.758	0.501373	3.47043	13.2764	0	0	0	
+5.759	0.500508	3.46645	13.2724	0	0	0	
+5.76	0.499642	3.46245	13.2684	0	0	0	
+5.761	0.498775	3.45843	13.2644	0	0	0	
+5.762	0.497908	3.45441	13.2604	0	0	0	
+5.763	0.497041	3.45037	13.2564	0	0	0	
+5.764	0.496173	3.44631	13.2523	0	0	0	
+5.765	0.495304	3.44225	13.2482	0	0	0	
+5.766	0.494436	3.43816	13.2442	0	0	0	
+5.767	0.493566	3.43407	13.2401	0	0	0	
+5.768	0.492696	3.42996	13.236	0	0	0	
+5.769	0.491826	3.42584	13.2318	0	0	0	
+5.77	0.490955	3.4217	13.2277	0	0	0	
+5.771	0.490083	3.41755	13.2235	0	0	0	
+5.772	0.489211	3.41339	13.2194	0	0	0	
+5.773	0.488339	3.40921	13.2152	0	0	0	
+5.774	0.487466	3.40502	13.211	0	0	0	
+5.775	0.486593	3.40081	13.2068	0	0	0	
+5.776	0.485719	3.39659	13.2026	0	0	0	
+5.777	0.484844	3.39236	13.1984	0	0	0	
+5.778	0.48397	3.38812	13.1941	0	0	0	
+5.779	0.483094	3.38386	13.1899	0	0	0	
+5.78	0.482218	3.37958	13.1856	0	0	0	
+5.781	0.481342	3.3753	13.1813	0	0	0	
+5.782	0.480465	3.371	13.177	0	0	0	
+5.783	0.479588	3.36668	13.1727	0	0	0	
+5.784	0.47871	3.36236	13.1684	0	0	0	
+5.785	0.477832	3.35802	13.164	0	0	0	
+5.786	0.476954	3.35366	13.1597	0	0	0	
+5.787	0.476074	3.3493	13.1553	0	0	0	
+5.788	0.475195	3.34492	13.1509	0	0	0	
+5.789	0.474315	3.34052	13.1465	0	0	0	
+5.79	0.473434	3.33612	13.1421	0	0	0	
+5.791	0.472553	3.3317	13.1377	0	0	0	
+5.792	0.471671	3.32726	13.1333	0	0	0	
+5.793	0.470789	3.32282	13.1288	0	0	0	
+5.794	0.469907	3.31835	13.1244	0	0	0	
+5.795	0.469024	3.31388	13.1199	0	0	0	
+5.796	0.468141	3.30939	13.1154	0	0	0	
+5.797	0.467257	3.30489	13.1109	0	0	0	
+5.798	0.466372	3.30038	13.1064	0	0	0	
+5.799	0.465487	3.29585	13.1019	0	0	0	
+5.8	0.464602	3.29131	13.0973	0	0	0	
+5.801	0.463716	3.28676	13.0928	0	0	0	
+5.802	0.46283	3.2822	13.0882	0	0	0	
+5.803	0.461944	3.27762	13.0836	0	0	0	
+5.804	0.461056	3.27302	13.079	0	0	0	
+5.805	0.460169	3.26842	13.0744	0	0	0	
+5.806	0.459281	3.2638	13.0698	0	0	0	
+5.807	0.458392	3.25917	13.0652	0	0	0	
+5.808	0.457503	3.25452	13.0605	0	0	0	
+5.809	0.456614	3.24987	13.0559	0	0	0	
+5.81	0.455724	3.2452	13.0512	0	0	0	
+5.811	0.454834	3.24051	13.0465	0	0	0	
+5.812	0.453943	3.23582	13.0418	0	0	0	
+5.813	0.453051	3.23111	13.0371	0	0	0	
+5.814	0.45216	3.22638	13.0324	0	0	0	
+5.815	0.451268	3.22165	13.0276	0	0	0	
+5.816	0.450375	3.2169	13.0229	0	0	0	
+5.817	0.449482	3.21214	13.0181	0	0	0	
+5.818	0.448588	3.20737	13.0134	0	0	0	
+5.819	0.447694	3.20258	13.0086	0	0	0	
+5.82	0.4468	3.19778	13.0038	0	0	0	
+5.821	0.445905	3.19297	12.999	0	0	0	
+5.822	0.44501	3.18814	12.9941	0	0	0	
+5.823	0.444114	3.1833	12.9893	0	0	0	
+5.824	0.443218	3.17845	12.9845	0	0	0	
+5.825	0.442321	3.17359	12.9796	0	0	0	
+5.826	0.441424	3.16871	12.9747	0	0	0	
+5.827	0.440527	3.16383	12.9698	0	0	0	
+5.828	0.439629	3.15892	12.9649	0	0	0	
+5.829	0.43873	3.15401	12.96	0	0	0	
+5.83	0.437832	3.14908	12.9551	0	0	0	
+5.831	0.436932	3.14414	12.9501	0	0	0	
+5.832	0.436033	3.13919	12.9452	0	0	0	
+5.833	0.435132	3.13423	12.9402	0	0	0	
+5.834	0.434232	3.12925	12.9353	0	0	0	
+5.835	0.433331	3.12426	12.9303	0	0	0	
+5.836	0.432429	3.11926	12.9253	0	0	0	
+5.837	0.431527	3.11425	12.9202	0	0	0	
+5.838	0.430625	3.10922	12.9152	0	0	0	
+5.839	0.429722	3.10418	12.9102	0	0	0	
+5.84	0.428819	3.09913	12.9051	0	0	0	
+5.841	0.427916	3.09407	12.9001	0	0	0	
+5.842	0.427012	3.08899	12.895	0	0	0	
+5.843	0.426107	3.0839	12.8899	0	0	0	
+5.844	0.425202	3.0788	12.8848	0	0	0	
+5.845	0.424297	3.07369	12.8797	0	0	0	
+5.846	0.423391	3.06856	12.8746	0	0	0	
+5.847	0.422485	3.06342	12.8694	0	0	0	
+5.848	0.421578	3.05827	12.8643	0	0	0	
+5.849	0.420671	3.05311	12.8591	0	0	0	
+5.85	0.419764	3.04793	12.8539	0	0	0	
+5.851	0.418856	3.04275	12.8487	0	0	0	
+5.852	0.417948	3.03755	12.8435	0	0	0	
+5.853	0.417039	3.03234	12.8383	0	0	0	
+5.854	0.41613	3.02711	12.8331	0	0	0	
+5.855	0.415221	3.02188	12.8279	0	0	0	
+5.856	0.414311	3.01663	12.8226	0	0	0	
+5.857	0.4134	3.01137	12.8174	0	0	0	
+5.858	0.41249	3.0061	12.8121	0	0	0	
+5.859	0.411578	3.00082	12.8068	0	0	0	
+5.86	0.410667	2.99552	12.8015	0	0	0	
+5.861	0.409755	2.99021	12.7962	0	0	0	
+5.862	0.408842	2.98489	12.7909	0	0	0	
+5.863	0.40793	2.97956	12.7856	0	0	0	
+5.864	0.407016	2.97422	12.7802	0	0	0	
+5.865	0.406103	2.96886	12.7749	0	0	0	
+5.866	0.405189	2.9635	12.7695	0	0	0	
+5.867	0.404274	2.95812	12.7641	0	0	0	
+5.868	0.40336	2.95273	12.7587	0	0	0	
+5.869	0.402444	2.94732	12.7533	0	0	0	
+5.87	0.401529	2.94191	12.7479	0	0	0	
+5.871	0.400613	2.93648	12.7425	0	0	0	
+5.872	0.399696	2.93104	12.737	0	0	0	
+5.873	0.398779	2.92559	12.7316	0	0	0	
+5.874	0.397862	2.92013	12.7261	0	0	0	
+5.875	0.396944	2.91466	12.7207	0	0	0	
+5.876	0.396026	2.90918	12.7152	0	0	0	
+5.877	0.395108	2.90368	12.7097	0	0	0	
+5.878	0.394189	2.89817	12.7042	0	0	0	
+5.879	0.39327	2.89265	12.6987	0	0	0	
+5.88	0.39235	2.88712	12.6931	0	0	0	
+5.881	0.39143	2.88158	12.6876	0	0	0	
+5.882	0.39051	2.87602	12.682	0	0	0	
+5.883	0.389589	2.87046	12.6765	0	0	0	
+5.884	0.388668	2.86488	12.6709	0	0	0	
+5.885	0.387746	2.85929	12.6653	0	0	0	
+5.886	0.386824	2.85369	12.6597	0	0	0	
+5.887	0.385902	2.84808	12.6541	0	0	0	
+5.888	0.384979	2.84246	12.6485	0	0	0	
+5.889	0.384056	2.83682	12.6428	0	0	0	
+5.89	0.383133	2.83118	12.6372	0	0	0	
+5.891	0.382209	2.82552	12.6315	0	0	0	
+5.892	0.381284	2.81985	12.6259	0	0	0	
+5.893	0.38036	2.81417	12.6202	0	0	0	
+5.894	0.379435	2.80848	12.6145	0	0	0	
+5.895	0.378509	2.80278	12.6088	0	0	0	
+5.896	0.377584	2.79707	12.6031	0	0	0	
+5.897	0.376657	2.79134	12.5973	0	0	0	
+5.898	0.375731	2.78561	12.5916	0	0	0	
+5.899	0.374804	2.77986	12.5859	0	0	0	
+5.9	0.373877	2.7741	12.5801	0	0	0	
+5.901	0.372949	2.76833	12.5743	0	0	0	
+5.902	0.372021	2.76255	12.5686	0	0	0	
+5.903	0.371093	2.75676	12.5628	0	0	0	
+5.904	0.370164	2.75096	12.557	0	0	0	
+5.905	0.369235	2.74514	12.5511	0	0	0	
+5.906	0.368305	2.73932	12.5453	0	0	0	
+5.907	0.367375	2.73349	12.5395	0	0	0	
+5.908	0.366445	2.72764	12.5336	0	0	0	
+5.909	0.365514	2.72178	12.5278	0	0	0	
+5.91	0.364583	2.71591	12.5219	0	0	0	
+5.911	0.363652	2.71004	12.516	0	0	0	
+5.912	0.36272	2.70415	12.5101	0	0	0	
+5.913	0.361788	2.69825	12.5042	0	0	0	
+5.914	0.360856	2.69234	12.4983	0	0	0	
+5.915	0.359923	2.68641	12.4924	0	0	0	
+5.916	0.35899	2.68048	12.4865	0	0	0	
+5.917	0.358056	2.67454	12.4805	0	0	0	
+5.918	0.357122	2.66858	12.4746	0	0	0	
+5.919	0.356188	2.66262	12.4686	0	0	0	
+5.92	0.355254	2.65664	12.4626	0	0	0	
+5.921	0.354319	2.65066	12.4567	0	0	0	
+5.922	0.353383	2.64466	12.4507	0	0	0	
+5.923	0.352448	2.63865	12.4447	0	0	0	
+5.924	0.351512	2.63264	12.4386	0	0	0	
+5.925	0.350575	2.62661	12.4326	0	0	0	
+5.926	0.349639	2.62057	12.4266	0	0	0	
+5.927	0.348702	2.61452	12.4205	0	0	0	
+5.928	0.347764	2.60846	12.4145	0	0	0	
+5.929	0.346826	2.60239	12.4084	0	0	0	
+5.93	0.345888	2.59631	12.4023	0	0	0	
+5.931	0.34495	2.59022	12.3962	0	0	0	
+5.932	0.344011	2.58412	12.3901	0	0	0	
+5.933	0.343072	2.578	12.384	0	0	0	
+5.934	0.342132	2.57188	12.3779	0	0	0	
+5.935	0.341193	2.56575	12.3718	0	0	0	
+5.936	0.340252	2.55961	12.3656	0	0	0	
+5.937	0.339312	2.55345	12.3595	0	0	0	
+5.938	0.338371	2.54729	12.3533	0	0	0	
+5.939	0.33743	2.54112	12.3471	0	0	0	
+5.94	0.336488	2.53494	12.3409	0	0	0	
+5.941	0.335547	2.52874	12.3347	0	0	0	
+5.942	0.334604	2.52254	12.3285	0	0	0	
+5.943	0.333662	2.51632	12.3223	0	0	0	
+5.944	0.332719	2.5101	12.3161	0	0	0	
+5.945	0.331776	2.50387	12.3099	0	0	0	
+5.946	0.330832	2.49762	12.3036	0	0	0	
+5.947	0.329888	2.49137	12.2974	0	0	0	
+5.948	0.328944	2.48511	12.2911	0	0	0	
+5.949	0.328	2.47883	12.2848	0	0	0	
+5.95	0.327055	2.47255	12.2785	0	0	0	
+5.951	0.32611	2.46625	12.2723	0	0	0	
+5.952	0.325164	2.45995	12.266	0	0	0	
+5.953	0.324218	2.45364	12.2596	0	0	0	
+5.954	0.323272	2.44732	12.2533	0	0	0	
+5.955	0.322326	2.44098	12.247	0	0	0	
+5.956	0.321379	2.43464	12.2406	0	0	0	
+5.957	0.320432	2.42829	12.2343	0	0	0	
+5.958	0.319484	2.42193	12.2279	0	0	0	
+5.959	0.318537	2.41555	12.2216	0	0	0	
+5.96	0.317589	2.40917	12.2152	0	0	0	
+5.961	0.31664	2.40278	12.2088	0	0	0	
+5.962	0.315691	2.39638	12.2024	0	0	0	
+5.963	0.314742	2.38997	12.196	0	0	0	
+5.964	0.313793	2.38355	12.1896	0	0	0	
+5.965	0.312843	2.37712	12.1831	0	0	0	
+5.966	0.311894	2.37068	12.1767	0	0	0	
+5.967	0.310943	2.36423	12.1702	0	0	0	
+5.968	0.309993	2.35778	12.1638	0	0	0	
+5.969	0.309042	2.35131	12.1573	0	0	0	
+5.97	0.308091	2.34483	12.1508	0	0	0	
+5.971	0.307139	2.33835	12.1443	0	0	0	
+5.972	0.306187	2.33185	12.1379	0	0	0	
+5.973	0.305235	2.32535	12.1313	0	0	0	
+5.974	0.304283	2.31883	12.1248	0	0	0	
+5.975	0.30333	2.31231	12.1183	0	0	0	
+5.976	0.302377	2.30578	12.1118	0	0	0	
+5.977	0.301424	2.29924	12.1052	0	0	0	
+5.978	0.30047	2.29268	12.0987	0	0	0	
+5.979	0.299516	2.28612	12.0921	0	0	0	
+5.98	0.298562	2.27956	12.0856	0	0	0	
+5.981	0.297607	2.27298	12.079	0	0	0	
+5.982	0.296652	2.26639	12.0724	0	0	0	
+5.983	0.295697	2.25979	12.0658	0	0	0	
+5.984	0.294742	2.25319	12.0592	0	0	0	
+5.985	0.293786	2.24657	12.0526	0	0	0	
+5.986	0.29283	2.23995	12.0459	0	0	0	
+5.987	0.291874	2.23332	12.0393	0	0	0	
+5.988	0.290917	2.22668	12.0327	0	0	0	
+5.989	0.28996	2.22003	12.026	0	0	0	
+5.99	0.289003	2.21337	12.0194	0	0	0	
+5.991	0.288046	2.2067	12.0127	0	0	0	
+5.992	0.287088	2.20002	12.006	0	0	0	
+5.993	0.28613	2.19334	11.9993	0	0	0	
+5.994	0.285171	2.18664	11.9926	0	0	0	
+5.995	0.284213	2.17994	11.9859	0	0	0	
+5.996	0.283254	2.17323	11.9792	0	0	0	
+5.997	0.282295	2.16651	11.9725	0	0	0	
+5.998	0.281335	2.15978	11.9658	0	0	0	
+5.999	0.280376	2.15304	11.959	0	0	0	
+6	0.279415	2.14629	11.9523	0	0	0	
+6.001	0.278455	2.13954	11.9455	0	0	0	
+6.002	0.277495	2.13277	11.9388	0	0	0	
+6.003	0.276534	2.126	11.932	0	0	0	
+6.004	0.275573	2.11922	11.9252	0	0	0	
+6.005	0.274611	2.11243	11.9184	0	0	0	
+6.006	0.273649	2.10563	11.9116	0	0	0	
+6.007	0.272688	2.09883	11.9048	0	0	0	
+6.008	0.271725	2.09201	11.898	0	0	0	
+6.009	0.270763	2.08519	11.8912	0	0	0	
+6.01	0.2698	2.07836	11.8844	0	0	0	
+6.011	0.268837	2.07152	11.8775	0	0	0	
+6.012	0.267874	2.06467	11.8707	0	0	0	
+6.013	0.26691	2.05782	11.8638	0	0	0	
+6.014	0.265946	2.05095	11.857	0	0	0	
+6.015	0.264982	2.04408	11.8501	0	0	0	
+6.016	0.264018	2.0372	11.8432	0	0	0	
+6.017	0.263053	2.03031	11.8363	0	0	0	
+6.018	0.262088	2.02341	11.8294	0	0	0	
+6.019	0.261123	2.01651	11.8225	0	0	0	
+6.02	0.260157	2.00959	11.8156	0	0	0	
+6.021	0.259192	2.00267	11.8087	0	0	0	
+6.022	0.258226	1.99574	11.8017	0	0	0	
+6.023	0.25726	1.98881	11.7948	0	0	0	
+6.024	0.256293	1.98186	11.7879	0	0	0	
+6.025	0.255326	1.97491	11.7809	0	0	0	
+6.026	0.254359	1.96795	11.7739	0	0	0	
+6.027	0.253392	1.96098	11.767	0	0	0	
+6.028	0.252425	1.954	11.76	0	0	0	
+6.029	0.251457	1.94702	11.753	0	0	0	
+6.03	0.250489	1.94003	11.746	0	0	0	
+6.031	0.249521	1.93303	11.739	0	0	0	
+6.032	0.248552	1.92602	11.732	0	0	0	
+6.033	0.247584	1.919	11.725	0	0	0	
+6.034	0.246615	1.91198	11.718	0	0	0	
+6.035	0.245645	1.90495	11.7109	0	0	0	
+6.036	0.244676	1.89791	11.7039	0	0	0	
+6.037	0.243706	1.89086	11.6969	0	0	0	
+6.038	0.242736	1.88381	11.6898	0	0	0	
+6.039	0.241766	1.87675	11.6828	0	0	0	
+6.04	0.240795	1.86968	11.6757	0	0	0	
+6.041	0.239825	1.86261	11.6686	0	0	0	
+6.042	0.238854	1.85552	11.6615	0	0	0	
+6.043	0.237883	1.84843	11.6544	0	0	0	
+6.044	0.236911	1.84133	11.6473	0	0	0	
+6.045	0.23594	1.83423	11.6402	0	0	0	
+6.046	0.234968	1.82711	11.6331	0	0	0	
+6.047	0.233996	1.81999	11.626	0	0	0	
+6.048	0.233023	1.81287	11.6189	0	0	0	
+6.049	0.232051	1.80573	11.6117	0	0	0	
+6.05	0.231078	1.79859	11.6046	0	0	0	
+6.051	0.230105	1.79144	11.5974	0	0	0	
+6.052	0.229131	1.78428	11.5903	0	0	0	
+6.053	0.228158	1.77712	11.5831	0	0	0	
+6.054	0.227184	1.76995	11.576	0	0	0	
+6.055	0.22621	1.76277	11.5688	0	0	0	
+6.056	0.225236	1.75559	11.5616	0	0	0	
+6.057	0.224262	1.7484	11.5544	0	0	0	
+6.058	0.223287	1.7412	11.5472	0	0	0	
+6.059	0.222312	1.73399	11.54	0	0	0	
+6.06	0.221337	1.72678	11.5328	0	0	0	
+6.061	0.220362	1.71956	11.5256	0	0	0	
+6.062	0.219386	1.71233	11.5183	0	0	0	
+6.063	0.21841	1.7051	11.5111	0	0	0	
+6.064	0.217434	1.69786	11.5039	0	0	0	
+6.065	0.216458	1.69061	11.4966	0	0	0	
+6.066	0.215482	1.68336	11.4894	0	0	0	
+6.067	0.214505	1.6761	11.4821	0	0	0	
+6.068	0.213528	1.66883	11.4748	0	0	0	
+6.069	0.212551	1.66156	11.4676	0	0	0	
+6.07	0.211574	1.65428	11.4603	0	0	0	
+6.071	0.210597	1.64699	11.453	0	0	0	
+6.072	0.209619	1.6397	11.4457	0	0	0	
+6.073	0.208641	1.6324	11.4384	0	0	0	
+6.074	0.207663	1.62509	11.4311	0	0	0	
+6.075	0.206685	1.61778	11.4238	0	0	0	
+6.076	0.205706	1.61046	11.4165	0	0	0	
+6.077	0.204728	1.60313	11.4091	0	0	0	
+6.078	0.203749	1.5958	11.4018	0	0	0	
+6.079	0.202769	1.58846	11.3945	0	0	0	
+6.08	0.20179	1.58111	11.3871	0	0	0	
+6.081	0.200811	1.57376	11.3798	0	0	0	
+6.082	0.199831	1.5664	11.3724	0	0	0	
+6.083	0.198851	1.55904	11.365	0	0	0	
+6.084	0.197871	1.55167	11.3577	0	0	0	
+6.085	0.19689	1.54429	11.3503	0	0	0	
+6.086	0.19591	1.53691	11.3429	0	0	0	
+6.087	0.194929	1.52952	11.3355	0	0	0	
+6.088	0.193948	1.52212	11.3281	0	0	0	
+6.089	0.192967	1.51472	11.3207	0	0	0	
+6.09	0.191986	1.50732	11.3133	0	0	0	
+6.091	0.191004	1.4999	11.3059	0	0	0	
+6.092	0.190023	1.49248	11.2985	0	0	0	
+6.093	0.189041	1.48506	11.2911	0	0	0	
+6.094	0.188059	1.47763	11.2836	0	0	0	
+6.095	0.187077	1.47019	11.2762	0	0	0	
+6.096	0.186094	1.46275	11.2687	0	0	0	
+6.097	0.185111	1.4553	11.2613	0	0	0	
+6.098	0.184129	1.44784	11.2538	0	0	0	
+6.099	0.183146	1.44038	11.2464	0	0	0	
+6.1	0.182163	1.43292	11.2389	0	0	0	
+6.101	0.181179	1.42545	11.2314	0	0	0	
+6.102	0.180196	1.41797	11.224	0	0	0	
+6.103	0.179212	1.41048	11.2165	0	0	0	
+6.104	0.178228	1.403	11.209	0	0	0	
+6.105	0.177244	1.3955	11.2015	0	0	0	
+6.106	0.17626	1.388	11.194	0	0	0	
+6.107	0.175275	1.38049	11.1865	0	0	0	
+6.108	0.174291	1.37298	11.179	0	0	0	
+6.109	0.173306	1.36547	11.1715	0	0	0	
+6.11	0.172321	1.35794	11.1639	0	0	0	
+6.111	0.171336	1.35042	11.1564	0	0	0	
+6.112	0.17035	1.34288	11.1489	0	0	0	
+6.113	0.169365	1.33535	11.1413	0	0	0	
+6.114	0.168379	1.3278	11.1338	0	0	0	
+6.115	0.167394	1.32025	11.1263	0	0	0	
+6.116	0.166408	1.3127	11.1187	0	0	0	
+6.117	0.165421	1.30514	11.1111	0	0	0	
+6.118	0.164435	1.29757	11.1036	0	0	0	
+6.119	0.163449	1.29	11.096	0	0	0	
+6.12	0.162462	1.28243	11.0884	0	0	0	
+6.121	0.161475	1.27485	11.0808	0	0	0	
+6.122	0.160488	1.26726	11.0733	0	0	0	
+6.123	0.159501	1.25967	11.0657	0	0	0	
+6.124	0.158514	1.25208	11.0581	0	0	0	
+6.125	0.157526	1.24448	11.0505	0	0	0	
+6.126	0.156539	1.23687	11.0429	0	0	0	
+6.127	0.155551	1.22926	11.0353	0	0	0	
+6.128	0.154563	1.22165	11.0276	0	0	0	
+6.129	0.153575	1.21403	11.02	0	0	0	
+6.13	0.152587	1.2064	11.0124	0	0	0	
+6.131	0.151599	1.19877	11.0048	0	0	0	
+6.132	0.15061	1.19114	10.9971	0	0	0	
+6.133	0.149621	1.1835	10.9895	0	0	0	
+6.134	0.148633	1.17585	10.9819	0	0	0	
+6.135	0.147644	1.1682	10.9742	0	0	0	
+6.136	0.146654	1.16055	10.9666	0	0	0	
+6.137	0.145665	1.15289	10.9589	0	0	0	
+6.138	0.144676	1.14523	10.9512	0	0	0	
+6.139	0.143686	1.13756	10.9436	0	0	0	
+6.14	0.142697	1.12989	10.9359	0	0	0	
+6.141	0.141707	1.12221	10.9282	0	0	0	
+6.142	0.140717	1.11453	10.9205	0	0	0	
+6.143	0.139727	1.10685	10.9128	0	0	0	
+6.144	0.138736	1.09916	10.9052	0	0	0	
+6.145	0.137746	1.09146	10.8975	0	0	0	
+6.146	0.136755	1.08376	10.8898	0	0	0	
+6.147	0.135765	1.07606	10.8821	0	0	0	
+6.148	0.134774	1.06835	10.8744	0	0	0	
+6.149	0.133783	1.06064	10.8666	0	0	0	
+6.15	0.132792	1.05293	10.8589	0	0	0	
+6.151	0.131801	1.04521	10.8512	0	0	0	
+6.152	0.130809	1.03748	10.8435	0	0	0	
+6.153	0.129818	1.02975	10.8358	0	0	0	
+6.154	0.128826	1.02202	10.828	0	0	0	
+6.155	0.127835	1.01429	10.8203	0	0	0	
+6.156	0.126843	1.00655	10.8125	0	0	0	
+6.157	0.125851	0.998801	10.8048	0	0	0	
+6.158	0.124859	0.991052	10.7971	0	0	0	
+6.159	0.123866	0.9833	10.7893	0	0	0	
+6.16	0.122874	0.975543	10.7815	0	0	0	
+6.161	0.121882	0.967783	10.7738	0	0	0	
+6.162	0.120889	0.960018	10.766	0	0	0	
+6.163	0.119896	0.95225	10.7583	0	0	0	
+6.164	0.118903	0.944479	10.7505	0	0	0	
+6.165	0.11791	0.936703	10.7427	0	0	0	
+6.166	0.116917	0.928923	10.7349	0	0	0	
+6.167	0.115924	0.92114	10.7271	0	0	0	
+6.168	0.114931	0.913353	10.7194	0	0	0	
+6.169	0.113937	0.905563	10.7116	0	0	0	
+6.17	0.112944	0.897769	10.7038	0	0	0	
+6.171	0.11195	0.889971	10.696	0	0	0	
+6.172	0.110956	0.88217	10.6882	0	0	0	
+6.173	0.109962	0.874365	10.6804	0	0	0	
+6.174	0.108968	0.866557	10.6726	0	0	0	
+6.175	0.107974	0.858745	10.6647	0	0	0	
+6.176	0.10698	0.85093	10.6569	0	0	0	
+6.177	0.105986	0.843111	10.6491	0	0	0	
+6.178	0.104991	0.835289	10.6413	0	0	0	
+6.179	0.103997	0.827464	10.6335	0	0	0	
+6.18	0.103002	0.819636	10.6256	0	0	0	
+6.181	0.102008	0.811804	10.6178	0	0	0	
+6.182	0.101013	0.803969	10.61	0	0	0	
+6.183	0.100018	0.79613	10.6021	0	0	0	
+6.184	0.0990228	0.788289	10.5943	0	0	0	
+6.185	0.0980276	0.780444	10.5864	0	0	0	
+6.186	0.0970324	0.772596	10.5786	0	0	0	
+6.187	0.0960371	0.764745	10.5707	0	0	0	
+6.188	0.0950416	0.756891	10.5629	0	0	0	
+6.189	0.0940461	0.749034	10.555	0	0	0	
+6.19	0.0930505	0.741174	10.5472	0	0	0	
+6.191	0.0920548	0.733311	10.5393	0	0	0	
+6.192	0.091059	0.725446	10.5314	0	0	0	
+6.193	0.0900631	0.717577	10.5236	0	0	0	
+6.194	0.0890671	0.709705	10.5157	0	0	0	
+6.195	0.0880711	0.701831	10.5078	0	0	0	
+6.196	0.0870749	0.693953	10.5	0	0	0	
+6.197	0.0860787	0.686073	10.4921	0	0	0	
+6.198	0.0850823	0.67819	10.4842	0	0	0	
+6.199	0.0840859	0.670305	10.4763	0	0	0	
+6.2	0.0830894	0.662417	10.4684	0	0	0	
+6.201	0.0820928	0.654526	10.4605	0	0	0	
+6.202	0.0810962	0.646632	10.4526	0	0	0	
+6.203	0.0800994	0.638736	10.4447	0	0	0	
+6.204	0.0791026	0.630838	10.4368	0	0	0	
+6.205	0.0781057	0.622937	10.4289	0	0	0	
+6.206	0.0771087	0.615033	10.421	0	0	0	
+6.207	0.0761116	0.607127	10.4131	0	0	0	
+6.208	0.0751145	0.599218	10.4052	0	0	0	
+6.209	0.0741173	0.591307	10.3973	0	0	0	
+6.21	0.07312	0.583394	10.3894	0	0	0	
+6.211	0.0721226	0.575478	10.3815	0	0	0	
+6.212	0.0711252	0.567561	10.3736	0	0	0	
+6.213	0.0701277	0.55964	10.3656	0	0	0	
+6.214	0.0691301	0.551718	10.3577	0	0	0	
+6.215	0.0681325	0.543793	10.3498	0	0	0	
+6.216	0.0671348	0.535867	10.3419	0	0	0	
+6.217	0.066137	0.527938	10.3339	0	0	0	
+6.218	0.0651392	0.520006	10.326	0	0	0	
+6.219	0.0641412	0.512073	10.3181	0	0	0	
+6.22	0.0631433	0.504138	10.3101	0	0	0	
+6.221	0.0621452	0.496201	10.3022	0	0	0	
+6.222	0.0611471	0.488262	10.2943	0	0	0	
+6.223	0.060149	0.480321	10.2863	0	0	0	
+6.224	0.0591508	0.472378	10.2784	0	0	0	
+6.225	0.0581525	0.464433	10.2704	0	0	0	
+6.226	0.0571541	0.456486	10.2625	0	0	0	
+6.227	0.0561558	0.448537	10.2545	0	0	0	
+6.228	0.0551573	0.440587	10.2466	0	0	0	
+6.229	0.0541588	0.432634	10.2386	0	0	0	
+6.23	0.0531602	0.424681	10.2307	0	0	0	
+6.231	0.0521616	0.416725	10.2227	0	0	0	
+6.232	0.051163	0.408768	10.2148	0	0	0	
+6.233	0.0501642	0.400809	10.2068	0	0	0	
+6.234	0.0491655	0.392848	10.1988	0	0	0	
+6.235	0.0481667	0.384886	10.1909	0	0	0	
+6.236	0.0471678	0.376922	10.1829	0	0	0	
+6.237	0.0461689	0.368957	10.175	0	0	0	
+6.238	0.0451699	0.360991	10.167	0	0	0	
+6.239	0.0441709	0.353023	10.159	0	0	0	
+6.24	0.0431719	0.345053	10.1511	0	0	0	
+6.241	0.0421728	0.337082	10.1431	0	0	0	
+6.242	0.0411737	0.32911	10.1351	0	0	0	
+6.243	0.0401745	0.321136	10.1271	0	0	0	
+6.244	0.0391753	0.313162	10.1192	0	0	0	
+6.245	0.038176	0.305186	10.1112	0	0	0	
+6.246	0.0371767	0.297208	10.1032	0	0	0	
+6.247	0.0361774	0.28923	10.0952	0	0	0	
+6.248	0.035178	0.28125	10.0873	0	0	0	
+6.249	0.0341786	0.273269	10.0793	0	0	0	
+6.25	0.0331792	0.265288	10.0713	0	0	0	
+6.251	0.0321798	0.257305	10.0633	0	0	0	
+6.252	0.0311803	0.249321	10.0553	0	0	0	
+6.253	0.0301807	0.241336	10.0473	0	0	0	
+6.254	0.0291812	0.23335	10.0393	0	0	0	
+6.255	0.0281816	0.225363	10.0314	0	0	0	
+6.256	0.027182	0.217375	10.0234	0	0	0	
+6.257	0.0261823	0.209387	10.0154	0	0	0	
+6.258	0.0251826	0.201397	10.0074	0	0	0	
+6.259	0.0241829	0.193407	9.99941	0	0	0	
+6.26	0.0231832	0.185416	9.99142	0	0	0	
+6.261	0.0221835	0.177424	9.98342	0	0	0	
+6.262	0.0211837	0.169432	9.97543	0	0	0	
+6.263	0.0201839	0.161439	9.96744	0	0	0	
+6.264	0.0191841	0.153445	9.95944	0	0	0	
+6.265	0.0181843	0.14545	9.95145	0	0	0	
+6.266	0.0171845	0.137455	9.94346	0	0	0	
+6.267	0.0161846	0.12946	9.93546	0	0	0	
+6.268	0.0151847	0.121464	9.92746	0	0	0	
+6.269	0.0141848	0.113467	9.91947	0	0	0	
+6.27	0.0131849	0.10547	9.91147	0	0	0	
+6.271	0.012185	0.0974728	9.90347	0	0	0	
+6.272	0.0111851	0.089475	9.89547	0	0	0	
+6.273	0.0101851	0.0814768	9.88748	0	0	0	
+6.274	0.00918518	0.0734783	9.87948	0	0	0	
+6.275	0.00818522	0.0654795	9.87148	0	0	0	
+6.276	0.00718525	0.0574805	9.86348	0	0	0	
+6.277	0.00618527	0.0494812	9.85548	0	0	0	
+6.278	0.00518528	0.0414817	9.84748	0	0	0	
+6.279	0.00418529	0.0334821	9.83948	0	0	0	
+6.28	0.0031853	0.0254823	9.83148	0	0	0	
+6.281	0.00218531	0.0174824	9.82348	0	0	0	
+6.282	0.00118531	0.00948245	9.81548	0	0	0	
+6.283	0.000185307	0.00148246	9.80748	0	0	0	
+6.284	-0.000814693	-0.00651754	9.79948	0	0	0	
+6.285	-0.00181469	-0.0145175	9.79148	0	0	0	
+6.286	-0.00281469	-0.0225174	9.78348	0	0	0	
+6.287	-0.00381468	-0.0305172	9.77548	0	0	0	
+6.288	-0.00481467	-0.0385169	9.76748	0	0	0	
+6.289	-0.00581466	-0.0465165	9.75948	0	0	0	
+6.29	-0.00681464	-0.0545159	9.75148	0	0	0	
+6.291	-0.00781461	-0.062515	9.74349	0	0	0	
+6.292	-0.00881458	-0.0705139	9.73549	0	0	0	
+6.293	-0.00981454	-0.0785125	9.72749	0	0	0	
+6.294	-0.0108145	-0.0865108	9.71949	0	0	0	
+6.295	-0.0118144	-0.0945087	9.71149	0	0	0	
+6.296	-0.0128143	-0.102506	9.70349	0	0	0	
+6.297	-0.0138143	-0.110503	9.6955	0	0	0	
+6.298	-0.0148142	-0.1185	9.6875	0	0	0	
+6.299	-0.015814	-0.126496	9.6795	0	0	0	
+6.3	-0.0168139	-0.134492	9.67151	0	0	0	
+6.301	-0.0178138	-0.142487	9.66351	0	0	0	
+6.302	-0.0188136	-0.150482	9.65552	0	0	0	
+6.303	-0.0198134	-0.158476	9.64752	0	0	0	
+6.304	-0.0208132	-0.166469	9.63953	0	0	0	
+6.305	-0.021813	-0.174462	9.63154	0	0	0	
+6.306	-0.0228127	-0.182454	9.62355	0	0	0	
+6.307	-0.0238124	-0.190446	9.61555	0	0	0	
+6.308	-0.0248121	-0.198436	9.60756	0	0	0	
+6.309	-0.0258118	-0.206426	9.59957	0	0	0	
+6.31	-0.0268115	-0.214415	9.59159	0	0	0	
+6.311	-0.0278111	-0.222403	9.5836	0	0	0	
+6.312	-0.0288107	-0.23039	9.57561	0	0	0	
+6.313	-0.0298103	-0.238376	9.56762	0	0	0	
+6.314	-0.0308098	-0.246362	9.55964	0	0	0	
+6.315	-0.0318093	-0.254346	9.55165	0	0	0	
+6.316	-0.0328088	-0.262329	9.54367	0	0	0	
+6.317	-0.0338082	-0.270311	9.53569	0	0	0	
+6.318	-0.0348077	-0.278293	9.52771	0	0	0	
+6.319	-0.035807	-0.286273	9.51973	0	0	0	
+6.32	-0.0368064	-0.294252	9.51175	0	0	0	
+6.321	-0.0378057	-0.302229	9.50377	0	0	0	
+6.322	-0.0388049	-0.310206	9.49579	0	0	0	
+6.323	-0.0398042	-0.318181	9.48782	0	0	0	
+6.324	-0.0408034	-0.326155	9.47984	0	0	0	
+6.325	-0.0418025	-0.334128	9.47187	0	0	0	
+6.326	-0.0428016	-0.342099	9.4639	0	0	0	
+6.327	-0.0438007	-0.350069	9.45593	0	0	0	
+6.328	-0.0447997	-0.358038	9.44796	0	0	0	
+6.329	-0.0457987	-0.366005	9.44	0	0	0	
+6.33	-0.0467976	-0.373971	9.43203	0	0	0	
+6.331	-0.0477965	-0.381935	9.42407	0	0	0	
+6.332	-0.0487953	-0.389897	9.4161	0	0	0	
+6.333	-0.0497941	-0.397859	9.40814	0	0	0	
+6.334	-0.0507928	-0.405818	9.40018	0	0	0	
+6.335	-0.0517915	-0.413776	9.39222	0	0	0	
+6.336	-0.0527901	-0.421732	9.38427	0	0	0	
+6.337	-0.0537887	-0.429687	9.37631	0	0	0	
+6.338	-0.0547872	-0.43764	9.36836	0	0	0	
+6.339	-0.0557857	-0.445591	9.36041	0	0	0	
+6.34	-0.0567841	-0.45354	9.35246	0	0	0	
+6.341	-0.0577825	-0.461488	9.34451	0	0	0	
+6.342	-0.0587808	-0.469433	9.33657	0	0	0	
+6.343	-0.059779	-0.477377	9.32862	0	0	0	
+6.344	-0.0607772	-0.485319	9.32068	0	0	0	
+6.345	-0.0617753	-0.493259	9.31274	0	0	0	
+6.346	-0.0627734	-0.501197	9.3048	0	0	0	
+6.347	-0.0637714	-0.509133	9.29687	0	0	0	
+6.348	-0.0647693	-0.517067	9.28893	0	0	0	
+6.349	-0.0657672	-0.524998	9.281	0	0	0	
+6.35	-0.066765	-0.532928	9.27307	0	0	0	
+6.351	-0.0677627	-0.540856	9.26514	0	0	0	
+6.352	-0.0687604	-0.548781	9.25722	0	0	0	
+6.353	-0.069758	-0.556704	9.2493	0	0	0	
+6.354	-0.0707555	-0.564625	9.24137	0	0	0	
+6.355	-0.071753	-0.572544	9.23346	0	0	0	
+6.356	-0.0727504	-0.580461	9.22554	0	0	0	
+6.357	-0.0737477	-0.588375	9.21763	0	0	0	
+6.358	-0.0747449	-0.596287	9.20971	0	0	0	
+6.359	-0.0757421	-0.604196	9.2018	0	0	0	
+6.36	-0.0767392	-0.612103	9.1939	0	0	0	
+6.361	-0.0777362	-0.620008	9.18599	0	0	0	
+6.362	-0.0787331	-0.62791	9.17809	0	0	0	
+6.363	-0.07973	-0.635809	9.17019	0	0	0	
+6.364	-0.0807268	-0.643706	9.16229	0	0	0	
+6.365	-0.0817235	-0.651601	9.1544	0	0	0	
+6.366	-0.0827201	-0.659493	9.14651	0	0	0	
+6.367	-0.0837166	-0.667382	9.13862	0	0	0	
+6.368	-0.084713	-0.675268	9.13073	0	0	0	
+6.369	-0.0857094	-0.683152	9.12285	0	0	0	
+6.37	-0.0867057	-0.691033	9.11497	0	0	0	
+6.371	-0.0877019	-0.698912	9.10709	0	0	0	
+6.372	-0.088698	-0.706787	9.09921	0	0	0	
+6.373	-0.089694	-0.71466	9.09134	0	0	0	
+6.374	-0.0906899	-0.72253	9.08347	0	0	0	
+6.375	-0.0916857	-0.730397	9.0756	0	0	0	
+6.376	-0.0926815	-0.738261	9.06774	0	0	0	
+6.377	-0.0936771	-0.746122	9.05988	0	0	0	
+6.378	-0.0946727	-0.75398	9.05202	0	0	0	
+6.379	-0.0956682	-0.761835	9.04417	0	0	0	
+6.38	-0.0966635	-0.769687	9.03631	0	0	0	
+6.381	-0.0976588	-0.777536	9.02846	0	0	0	
+6.382	-0.098654	-0.785382	9.02062	0	0	0	
+6.383	-0.099649	-0.793224	9.01278	0	0	0	
+6.384	-0.100644	-0.801064	9.00494	0	0	0	
+6.385	-0.101639	-0.8089	8.9971	0	0	0	
+6.386	-0.102634	-0.816733	8.98927	0	0	0	
+6.387	-0.103628	-0.824563	8.98144	0	0	0	
+6.388	-0.104623	-0.83239	8.97361	0	0	0	
+6.389	-0.105617	-0.840213	8.96579	0	0	0	
+6.39	-0.106612	-0.848033	8.95797	0	0	0	
+6.391	-0.107606	-0.855849	8.95015	0	0	0	
+6.392	-0.1086	-0.863662	8.94234	0	0	0	
+6.393	-0.109594	-0.871472	8.93453	0	0	0	
+6.394	-0.110588	-0.879278	8.92672	0	0	0	
+6.395	-0.111582	-0.88708	8.91892	0	0	0	
+6.396	-0.112576	-0.894879	8.91112	0	0	0	
+6.397	-0.113569	-0.902675	8.90333	0	0	0	
+6.398	-0.114563	-0.910467	8.89553	0	0	0	
+6.399	-0.115556	-0.918255	8.88775	0	0	0	
+6.4	-0.116549	-0.926039	8.87996	0	0	0	
+6.401	-0.117542	-0.93382	8.87218	0	0	0	
+6.402	-0.118535	-0.941597	8.8644	0	0	0	
+6.403	-0.119528	-0.94937	8.85663	0	0	0	
+6.404	-0.120521	-0.95714	8.84886	0	0	0	
+6.405	-0.121514	-0.964906	8.84109	0	0	0	
+6.406	-0.122506	-0.972667	8.83333	0	0	0	
+6.407	-0.123499	-0.980425	8.82557	0	0	0	
+6.408	-0.124491	-0.988179	8.81782	0	0	0	
+6.409	-0.125483	-0.995929	8.81007	0	0	0	
+6.41	-0.126475	-1.00368	8.80232	0	0	0	
+6.411	-0.127467	-1.01142	8.79458	0	0	0	
+6.412	-0.128459	-1.01916	8.78684	0	0	0	
+6.413	-0.12945	-1.02689	8.77911	0	0	0	
+6.414	-0.130442	-1.03462	8.77138	0	0	0	
+6.415	-0.131433	-1.04235	8.76365	0	0	0	
+6.416	-0.132425	-1.05007	8.75593	0	0	0	
+6.417	-0.133416	-1.05778	8.74822	0	0	0	
+6.418	-0.134407	-1.0655	8.7405	0	0	0	
+6.419	-0.135398	-1.07321	8.73279	0	0	0	
+6.42	-0.136388	-1.08091	8.72509	0	0	0	
+6.421	-0.137379	-1.08861	8.71739	0	0	0	
+6.422	-0.138369	-1.09631	8.70969	0	0	0	
+6.423	-0.13936	-1.104	8.702	0	0	0	
+6.424	-0.14035	-1.11168	8.69432	0	0	0	
+6.425	-0.14134	-1.11937	8.68663	0	0	0	
+6.426	-0.14233	-1.12705	8.67895	0	0	0	
+6.427	-0.143319	-1.13472	8.67128	0	0	0	
+6.428	-0.144309	-1.14239	8.66361	0	0	0	
+6.429	-0.145299	-1.15005	8.65595	0	0	0	
+6.43	-0.146288	-1.15771	8.64829	0	0	0	
+6.431	-0.147277	-1.16537	8.64063	0	0	0	
+6.432	-0.148266	-1.17302	8.63298	0	0	0	
+6.433	-0.149255	-1.18066	8.62534	0	0	0	
+6.434	-0.150244	-1.18831	8.61769	0	0	0	
+6.435	-0.151232	-1.19594	8.61006	0	0	0	
+6.436	-0.152221	-1.20357	8.60243	0	0	0	
+6.437	-0.153209	-1.2112	8.5948	0	0	0	
+6.438	-0.154197	-1.21882	8.58718	0	0	0	
+6.439	-0.155185	-1.22644	8.57956	0	0	0	
+6.44	-0.156173	-1.23405	8.57195	0	0	0	
+6.441	-0.15716	-1.24166	8.56434	0	0	0	
+6.442	-0.158148	-1.24926	8.55674	0	0	0	
+6.443	-0.159135	-1.25686	8.54914	0	0	0	
+6.444	-0.160122	-1.26445	8.54155	0	0	0	
+6.445	-0.161109	-1.27204	8.53396	0	0	0	
+6.446	-0.162096	-1.27962	8.52638	0	0	0	
+6.447	-0.163083	-1.2872	8.5188	0	0	0	
+6.448	-0.16407	-1.29477	8.51123	0	0	0	
+6.449	-0.165056	-1.30234	8.50366	0	0	0	
+6.45	-0.166042	-1.3099	8.4961	0	0	0	
+6.451	-0.167028	-1.31745	8.48855	0	0	0	
+6.452	-0.168014	-1.325	8.481	0	0	0	
+6.453	-0.169	-1.33255	8.47345	0	0	0	
+6.454	-0.169985	-1.34009	8.46591	0	0	0	
+6.455	-0.170971	-1.34763	8.45837	0	0	0	
+6.456	-0.171956	-1.35516	8.45084	0	0	0	
+6.457	-0.172941	-1.36268	8.44332	0	0	0	
+6.458	-0.173926	-1.3702	8.4358	0	0	0	
+6.459	-0.17491	-1.37771	8.42829	0	0	0	
+6.46	-0.175895	-1.38522	8.42078	0	0	0	
+6.461	-0.176879	-1.39272	8.41328	0	0	0	
+6.462	-0.177863	-1.40022	8.40578	0	0	0	
+6.463	-0.178847	-1.40771	8.39829	0	0	0	
+6.464	-0.179831	-1.41519	8.39081	0	0	0	
+6.465	-0.180815	-1.42267	8.38333	0	0	0	
+6.466	-0.181798	-1.43015	8.37585	0	0	0	
+6.467	-0.182781	-1.43762	8.36838	0	0	0	
+6.468	-0.183764	-1.44508	8.36092	0	0	0	
+6.469	-0.184747	-1.45254	8.35346	0	0	0	
+6.47	-0.18573	-1.45999	8.34601	0	0	0	
+6.471	-0.186712	-1.46743	8.33857	0	0	0	
+6.472	-0.187695	-1.47487	8.33113	0	0	0	
+6.473	-0.188677	-1.48231	8.32369	0	0	0	
+6.474	-0.189659	-1.48973	8.31627	0	0	0	
+6.475	-0.190641	-1.49715	8.30885	0	0	0	
+6.476	-0.191622	-1.50457	8.30143	0	0	0	
+6.477	-0.192604	-1.51198	8.29402	0	0	0	
+6.478	-0.193585	-1.51938	8.28662	0	0	0	
+6.479	-0.194566	-1.52678	8.27922	0	0	0	
+6.48	-0.195547	-1.53417	8.27183	0	0	0	
+6.481	-0.196527	-1.54156	8.26444	0	0	0	
+6.482	-0.197508	-1.54894	8.25706	0	0	0	
+6.483	-0.198488	-1.55631	8.24969	0	0	0	
+6.484	-0.199468	-1.56367	8.24233	0	0	0	
+6.485	-0.200448	-1.57103	8.23497	0	0	0	
+6.486	-0.201427	-1.57839	8.22761	0	0	0	
+6.487	-0.202407	-1.58574	8.22026	0	0	0	
+6.488	-0.203386	-1.59308	8.21292	0	0	0	
+6.489	-0.204365	-1.60041	8.20559	0	0	0	
+6.49	-0.205344	-1.60774	8.19826	0	0	0	
+6.491	-0.206322	-1.61506	8.19094	0	0	0	
+6.492	-0.2073	-1.62238	8.18362	0	0	0	
+6.493	-0.208279	-1.62969	8.17631	0	0	0	
+6.494	-0.209257	-1.63699	8.16901	0	0	0	
+6.495	-0.210234	-1.64429	8.16171	0	0	0	
+6.496	-0.211212	-1.65158	8.15442	0	0	0	
+6.497	-0.212189	-1.65886	8.14714	0	0	0	
+6.498	-0.213166	-1.66614	8.13986	0	0	0	
+6.499	-0.214143	-1.67341	8.13259	0	0	0	
+6.5	-0.21512	-1.68067	8.12533	0	0	0	
+6.501	-0.216096	-1.68792	8.11808	0	0	0	
+6.502	-0.217073	-1.69517	8.11083	0	0	0	
+6.503	-0.218049	-1.70242	8.10358	0	0	0	
+6.504	-0.219025	-1.70965	8.09635	0	0	0	
+6.505	-0.22	-1.71688	8.08912	0	0	0	
+6.506	-0.220976	-1.7241	8.0819	0	0	0	
+6.507	-0.221951	-1.73132	8.07468	0	0	0	
+6.508	-0.222926	-1.73853	8.06747	0	0	0	
+6.509	-0.2239	-1.74573	8.06027	0	0	0	
+6.51	-0.224875	-1.75292	8.05308	0	0	0	
+6.511	-0.225849	-1.76011	8.04589	0	0	0	
+6.512	-0.226823	-1.76729	8.03871	0	0	0	
+6.513	-0.227797	-1.77446	8.03154	0	0	0	
+6.514	-0.228771	-1.78163	8.02437	0	0	0	
+6.515	-0.229744	-1.78879	8.01721	0	0	0	
+6.516	-0.230717	-1.79594	8.01006	0	0	0	
+6.517	-0.23169	-1.80309	8.00291	0	0	0	
+6.518	-0.232663	-1.81022	7.99578	0	0	0	
+6.519	-0.233635	-1.81735	7.98865	0	0	0	
+6.52	-0.234607	-1.82448	7.98152	0	0	0	
+6.521	-0.235579	-1.83159	7.97441	0	0	0	
+6.522	-0.236551	-1.8387	7.9673	0	0	0	
+6.523	-0.237523	-1.8458	7.9602	0	0	0	
+6.524	-0.238494	-1.8529	7.9531	0	0	0	
+6.525	-0.239465	-1.85998	7.94602	0	0	0	
+6.526	-0.240436	-1.86706	7.93894	0	0	0	
+6.527	-0.241406	-1.87413	7.93187	0	0	0	
+6.528	-0.242377	-1.8812	7.9248	0	0	0	
+6.529	-0.243347	-1.88825	7.91775	0	0	0	
+6.53	-0.244316	-1.8953	7.9107	0	0	0	
+6.531	-0.245286	-1.90234	7.90366	0	0	0	
+6.532	-0.246255	-1.90938	7.89662	0	0	0	
+6.533	-0.247224	-1.9164	7.8896	0	0	0	
+6.534	-0.248193	-1.92342	7.88258	0	0	0	
+6.535	-0.249162	-1.93043	7.87557	0	0	0	
+6.536	-0.25013	-1.93743	7.86857	0	0	0	
+6.537	-0.251098	-1.94443	7.86157	0	0	0	
+6.538	-0.252066	-1.95142	7.85458	0	0	0	
+6.539	-0.253034	-1.95839	7.84761	0	0	0	
+6.54	-0.254001	-1.96537	7.84063	0	0	0	
+6.541	-0.254968	-1.97233	7.83367	0	0	0	
+6.542	-0.255935	-1.97929	7.82671	0	0	0	
+6.543	-0.256901	-1.98623	7.81977	0	0	0	
+6.544	-0.257868	-1.99317	7.81283	0	0	0	
+6.545	-0.258834	-2.00011	7.80589	0	0	0	
+6.546	-0.2598	-2.00703	7.79897	0	0	0	
+6.547	-0.260765	-2.01395	7.79205	0	0	0	
+6.548	-0.26173	-2.02085	7.78515	0	0	0	
+6.549	-0.262695	-2.02775	7.77825	0	0	0	
+6.55	-0.26366	-2.03465	7.77135	0	0	0	
+6.551	-0.264625	-2.04153	7.76447	0	0	0	
+6.552	-0.265589	-2.04841	7.75759	0	0	0	
+6.553	-0.266553	-2.05527	7.75073	0	0	0	
+6.554	-0.267517	-2.06213	7.74387	0	0	0	
+6.555	-0.26848	-2.06898	7.73702	0	0	0	
+6.556	-0.269443	-2.07582	7.73018	0	0	0	
+6.557	-0.270406	-2.08266	7.72334	0	0	0	
+6.558	-0.271369	-2.08948	7.71652	0	0	0	
+6.559	-0.272331	-2.0963	7.7097	0	0	0	
+6.56	-0.273293	-2.10311	7.70289	0	0	0	
+6.561	-0.274255	-2.10991	7.69609	0	0	0	
+6.562	-0.275216	-2.1167	7.6893	0	0	0	
+6.563	-0.276178	-2.12349	7.68251	0	0	0	
+6.564	-0.277139	-2.13026	7.67574	0	0	0	
+6.565	-0.278099	-2.13703	7.66897	0	0	0	
+6.566	-0.27906	-2.14379	7.66221	0	0	0	
+6.567	-0.28002	-2.15054	7.65546	0	0	0	
+6.568	-0.28098	-2.15728	7.64872	0	0	0	
+6.569	-0.281939	-2.16401	7.64199	0	0	0	
+6.57	-0.282898	-2.17074	7.63526	0	0	0	
+6.571	-0.283857	-2.17745	7.62855	0	0	0	
+6.572	-0.284816	-2.18416	7.62184	0	0	0	
+6.573	-0.285775	-2.19086	7.61514	0	0	0	
+6.574	-0.286733	-2.19754	7.60846	0	0	0	
+6.575	-0.287691	-2.20422	7.60178	0	0	0	
+6.576	-0.288648	-2.2109	7.5951	0	0	0	
+6.577	-0.289606	-2.21756	7.58844	0	0	0	
+6.578	-0.290563	-2.22421	7.58179	0	0	0	
+6.579	-0.291519	-2.23086	7.57514	0	0	0	
+6.58	-0.292476	-2.23749	7.56851	0	0	0	
+6.581	-0.293432	-2.24412	7.56188	0	0	0	
+6.582	-0.294388	-2.25074	7.55526	0	0	0	
+6.583	-0.295343	-2.25735	7.54865	0	0	0	
+6.584	-0.296298	-2.26395	7.54205	0	0	0	
+6.585	-0.297253	-2.27054	7.53546	0	0	0	
+6.586	-0.298208	-2.27712	7.52888	0	0	0	
+6.587	-0.299162	-2.28369	7.52231	0	0	0	
+6.588	-0.300116	-2.29025	7.51575	0	0	0	
+6.589	-0.30107	-2.29681	7.50919	0	0	0	
+6.59	-0.302024	-2.30335	7.50265	0	0	0	
+6.591	-0.302977	-2.30989	7.49611	0	0	0	
+6.592	-0.30393	-2.31642	7.48958	0	0	0	
+6.593	-0.304882	-2.32293	7.48307	0	0	0	
+6.594	-0.305834	-2.32944	7.47656	0	0	0	
+6.595	-0.306786	-2.33594	7.47006	0	0	0	
+6.596	-0.307738	-2.34243	7.46357	0	0	0	
+6.597	-0.308689	-2.34891	7.45709	0	0	0	
+6.598	-0.30964	-2.35538	7.45062	0	0	0	
+6.599	-0.310591	-2.36184	7.44416	0	0	0	
+6.6	-0.311541	-2.36829	7.43771	0	0	0	
+6.601	-0.312491	-2.37474	7.43126	0	0	0	
+6.602	-0.313441	-2.38117	7.42483	0	0	0	
+6.603	-0.314391	-2.38759	7.41841	0	0	0	
+6.604	-0.31534	-2.39401	7.41199	0	0	0	
+6.605	-0.316289	-2.40041	7.40559	0	0	0	
+6.606	-0.317237	-2.40681	7.39919	0	0	0	
+6.607	-0.318185	-2.41319	7.39281	0	0	0	
+6.608	-0.319133	-2.41957	7.38643	0	0	0	
+6.609	-0.320081	-2.42593	7.38007	0	0	0	
+6.61	-0.321028	-2.43229	7.37371	0	0	0	
+6.611	-0.321975	-2.43863	7.36737	0	0	0	
+6.612	-0.322921	-2.44497	7.36103	0	0	0	
+6.613	-0.323868	-2.4513	7.3547	0	0	0	
+6.614	-0.324814	-2.45761	7.34839	0	0	0	
+6.615	-0.325759	-2.46392	7.34208	0	0	0	
+6.616	-0.326705	-2.47022	7.33578	0	0	0	
+6.617	-0.32765	-2.4765	7.3295	0	0	0	
+6.618	-0.328594	-2.48278	7.32322	0	0	0	
+6.619	-0.329538	-2.48905	7.31695	0	0	0	
+6.62	-0.330482	-2.49531	7.31069	0	0	0	
+6.621	-0.331426	-2.50155	7.30445	0	0	0	
+6.622	-0.332369	-2.50779	7.29821	0	0	0	
+6.623	-0.333312	-2.51402	7.29198	0	0	0	
+6.624	-0.334255	-2.52024	7.28576	0	0	0	
+6.625	-0.335197	-2.52644	7.27956	0	0	0	
+6.626	-0.336139	-2.53264	7.27336	0	0	0	
+6.627	-0.337081	-2.53883	7.26717	0	0	0	
+6.628	-0.338022	-2.54501	7.26099	0	0	0	
+6.629	-0.338963	-2.55117	7.25483	0	0	0	
+6.63	-0.339904	-2.55733	7.24867	0	0	0	
+6.631	-0.340844	-2.56347	7.24253	0	0	0	
+6.632	-0.341784	-2.56961	7.23639	0	0	0	
+6.633	-0.342724	-2.57574	7.23026	0	0	0	
+6.634	-0.343663	-2.58185	7.22415	0	0	0	
+6.635	-0.344602	-2.58796	7.21804	0	0	0	
+6.636	-0.34554	-2.59405	7.21195	0	0	0	
+6.637	-0.346479	-2.60014	7.20586	0	0	0	
+6.638	-0.347417	-2.60621	7.19979	0	0	0	
+6.639	-0.348354	-2.61227	7.19373	0	0	0	
+6.64	-0.349291	-2.61833	7.18767	0	0	0	
+6.641	-0.350228	-2.62437	7.18163	0	0	0	
+6.642	-0.351165	-2.6304	7.1756	0	0	0	
+6.643	-0.352101	-2.63642	7.16958	0	0	0	
+6.644	-0.353037	-2.64244	7.16356	0	0	0	
+6.645	-0.353972	-2.64844	7.15756	0	0	0	
+6.646	-0.354907	-2.65443	7.15157	0	0	0	
+6.647	-0.355842	-2.6604	7.1456	0	0	0	
+6.648	-0.356776	-2.66637	7.13963	0	0	0	
+6.649	-0.35771	-2.67233	7.13367	0	0	0	
+6.65	-0.358644	-2.67828	7.12772	0	0	0	
+6.651	-0.359577	-2.68422	7.12178	0	0	0	
+6.652	-0.36051	-2.69014	7.11586	0	0	0	
+6.653	-0.361443	-2.69606	7.10994	0	0	0	
+6.654	-0.362375	-2.70196	7.10404	0	0	0	
+6.655	-0.363307	-2.70785	7.09815	0	0	0	
+6.656	-0.364238	-2.71374	7.09226	0	0	0	
+6.657	-0.365169	-2.71961	7.08639	0	0	0	
+6.658	-0.3661	-2.72547	7.08053	0	0	0	
+6.659	-0.36703	-2.73132	7.07468	0	0	0	
+6.66	-0.367961	-2.73716	7.06884	0	0	0	
+6.661	-0.36889	-2.74299	7.06301	0	0	0	
+6.662	-0.369819	-2.7488	7.0572	0	0	0	
+6.663	-0.370748	-2.75461	7.05139	0	0	0	
+6.664	-0.371677	-2.76041	7.04559	0	0	0	
+6.665	-0.372605	-2.76619	7.03981	0	0	0	
+6.666	-0.373533	-2.77196	7.03404	0	0	0	
+6.667	-0.37446	-2.77773	7.02827	0	0	0	
+6.668	-0.375387	-2.78348	7.02252	0	0	0	
+6.669	-0.376314	-2.78922	7.01678	0	0	0	
+6.67	-0.37724	-2.79494	7.01106	0	0	0	
+6.671	-0.378166	-2.80066	7.00534	0	0	0	
+6.672	-0.379092	-2.80637	6.99963	0	0	0	
+6.673	-0.380017	-2.81206	6.99394	0	0	0	
+6.674	-0.380942	-2.81775	6.98825	0	0	0	
+6.675	-0.381866	-2.82342	6.98258	0	0	0	
+6.676	-0.38279	-2.82908	6.97692	0	0	0	
+6.677	-0.383714	-2.83473	6.97127	0	0	0	
+6.678	-0.384637	-2.84037	6.96563	0	0	0	
+6.679	-0.38556	-2.846	6.96	0	0	0	
+6.68	-0.386483	-2.85161	6.95439	0	0	0	
+6.681	-0.387405	-2.85722	6.94878	0	0	0	
+6.682	-0.388326	-2.86281	6.94319	0	0	0	
+6.683	-0.389248	-2.86839	6.93761	0	0	0	
+6.684	-0.390169	-2.87396	6.93204	0	0	0	
+6.685	-0.391089	-2.87952	6.92648	0	0	0	
+6.686	-0.392009	-2.88507	6.92093	0	0	0	
+6.687	-0.392929	-2.8906	6.9154	0	0	0	
+6.688	-0.393848	-2.89613	6.90987	0	0	0	
+6.689	-0.394767	-2.90164	6.90436	0	0	0	
+6.69	-0.395686	-2.90714	6.89886	0	0	0	
+6.691	-0.396604	-2.91263	6.89337	0	0	0	
+6.692	-0.397522	-2.91811	6.88789	0	0	0	
+6.693	-0.398439	-2.92357	6.88243	0	0	0	
+6.694	-0.399356	-2.92903	6.87697	0	0	0	
+6.695	-0.400273	-2.93447	6.87153	0	0	0	
+6.696	-0.401189	-2.9399	6.8661	0	0	0	
+6.697	-0.402105	-2.94532	6.86068	0	0	0	
+6.698	-0.40302	-2.95072	6.85528	0	0	0	
+6.699	-0.403935	-2.95612	6.84988	0	0	0	
+6.7	-0.40485	-2.9615	6.8445	0	0	0	
+6.701	-0.405764	-2.96688	6.83912	0	0	0	
+6.702	-0.406678	-2.97223	6.83377	0	0	0	
+6.703	-0.407591	-2.97758	6.82842	0	0	0	
+6.704	-0.408504	-2.98292	6.82308	0	0	0	
+6.705	-0.409417	-2.98824	6.81776	0	0	0	
+6.706	-0.410329	-2.99355	6.81245	0	0	0	
+6.707	-0.411241	-2.99885	6.80715	0	0	0	
+6.708	-0.412152	-3.00414	6.80186	0	0	0	
+6.709	-0.413063	-3.00942	6.79658	0	0	0	
+6.71	-0.413973	-3.01468	6.79132	0	0	0	
+6.711	-0.414883	-3.01994	6.78606	0	0	0	
+6.712	-0.415793	-3.02518	6.78082	0	0	0	
+6.713	-0.416702	-3.0304	6.7756	0	0	0	
+6.714	-0.417611	-3.03562	6.77038	0	0	0	
+6.715	-0.41852	-3.04082	6.76518	0	0	0	
+6.716	-0.419428	-3.04601	6.75999	0	0	0	
+6.717	-0.420335	-3.05119	6.75481	0	0	0	
+6.718	-0.421242	-3.05636	6.74964	0	0	0	
+6.719	-0.422149	-3.06151	6.74449	0	0	0	
+6.72	-0.423055	-3.06666	6.73934	0	0	0	
+6.721	-0.423961	-3.07179	6.73421	0	0	0	
+6.722	-0.424867	-3.07691	6.72909	0	0	0	
+6.723	-0.425772	-3.08201	6.72399	0	0	0	
+6.724	-0.426676	-3.0871	6.7189	0	0	0	
+6.725	-0.427581	-3.09219	6.71381	0	0	0	
+6.726	-0.428484	-3.09725	6.70875	0	0	0	
+6.727	-0.429388	-3.10231	6.70369	0	0	0	
+6.728	-0.430291	-3.10735	6.69865	0	0	0	
+6.729	-0.431193	-3.11239	6.69361	0	0	0	
+6.73	-0.432095	-3.1174	6.6886	0	0	0	
+6.731	-0.432997	-3.12241	6.68359	0	0	0	
+6.732	-0.433898	-3.1274	6.6786	0	0	0	
+6.733	-0.434799	-3.13239	6.67361	0	0	0	
+6.734	-0.435699	-3.13735	6.66865	0	0	0	
+6.735	-0.436599	-3.14231	6.66369	0	0	0	
+6.736	-0.437498	-3.14726	6.65874	0	0	0	
+6.737	-0.438397	-3.15219	6.65381	0	0	0	
+6.738	-0.439296	-3.1571	6.6489	0	0	0	
+6.739	-0.440194	-3.16201	6.64399	0	0	0	
+6.74	-0.441092	-3.1669	6.6391	0	0	0	
+6.741	-0.441989	-3.17178	6.63422	0	0	0	
+6.742	-0.442886	-3.17665	6.62935	0	0	0	
+6.743	-0.443782	-3.18151	6.62449	0	0	0	
+6.744	-0.444678	-3.18635	6.61965	0	0	0	
+6.745	-0.445573	-3.19118	6.61482	0	0	0	
+6.746	-0.446468	-3.196	6.61	0	0	0	
+6.747	-0.447363	-3.2008	6.6052	0	0	0	
+6.748	-0.448257	-3.20559	6.60041	0	0	0	
+6.749	-0.449151	-3.21037	6.59563	0	0	0	
+6.75	-0.450044	-3.21514	6.59086	0	0	0	
+6.751	-0.450937	-3.21989	6.58611	0	0	0	
+6.752	-0.451829	-3.22463	6.58137	0	0	0	
+6.753	-0.452721	-3.22936	6.57664	0	0	0	
+6.754	-0.453612	-3.23407	6.57193	0	0	0	
+6.755	-0.454503	-3.23877	6.56723	0	0	0	
+6.756	-0.455394	-3.24346	6.56254	0	0	0	
+6.757	-0.456284	-3.24814	6.55786	0	0	0	
+6.758	-0.457174	-3.2528	6.5532	0	0	0	
+6.759	-0.458063	-3.25745	6.54855	0	0	0	
+6.76	-0.458951	-3.26209	6.54391	0	0	0	
+6.761	-0.45984	-3.26671	6.53929	0	0	0	
+6.762	-0.460727	-3.27132	6.53468	0	0	0	
+6.763	-0.461615	-3.27592	6.53008	0	0	0	
+6.764	-0.462502	-3.2805	6.5255	0	0	0	
+6.765	-0.463388	-3.28507	6.52093	0	0	0	
+6.766	-0.464274	-3.28963	6.51637	0	0	0	
+6.767	-0.465159	-3.29417	6.51183	0	0	0	
+6.768	-0.466044	-3.2987	6.5073	0	0	0	
+6.769	-0.466929	-3.30322	6.50278	0	0	0	
+6.77	-0.467813	-3.30773	6.49827	0	0	0	
+6.771	-0.468697	-3.31222	6.49378	0	0	0	
+6.772	-0.46958	-3.3167	6.4893	0	0	0	
+6.773	-0.470462	-3.32116	6.48484	0	0	0	
+6.774	-0.471345	-3.32562	6.48038	0	0	0	
+6.775	-0.472226	-3.33005	6.47595	0	0	0	
+6.776	-0.473108	-3.33448	6.47152	0	0	0	
+6.777	-0.473988	-3.33889	6.46711	0	0	0	
+6.778	-0.474869	-3.34329	6.46271	0	0	0	
+6.779	-0.475748	-3.34768	6.45832	0	0	0	
+6.78	-0.476628	-3.35205	6.45395	0	0	0	
+6.781	-0.477507	-3.35641	6.44959	0	0	0	
+6.782	-0.478385	-3.36075	6.44525	0	0	0	
+6.783	-0.479263	-3.36508	6.44092	0	0	0	
+6.784	-0.48014	-3.3694	6.4366	0	0	0	
+6.785	-0.481017	-3.37371	6.43229	0	0	0	
+6.786	-0.481894	-3.378	6.428	0	0	0	
+6.787	-0.48277	-3.38227	6.42373	0	0	0	
+6.788	-0.483645	-3.38654	6.41946	0	0	0	
+6.789	-0.48452	-3.39079	6.41521	0	0	0	
+6.79	-0.485395	-3.39503	6.41097	0	0	0	
+6.791	-0.486269	-3.39925	6.40675	0	0	0	
+6.792	-0.487142	-3.40346	6.40254	0	0	0	
+6.793	-0.488016	-3.40766	6.39834	0	0	0	
+6.794	-0.488888	-3.41184	6.39416	0	0	0	
+6.795	-0.48976	-3.41601	6.38999	0	0	0	
+6.796	-0.490632	-3.42016	6.38584	0	0	0	
+6.797	-0.491503	-3.4243	6.3817	0	0	0	
+6.798	-0.492374	-3.42843	6.37757	0	0	0	
+6.799	-0.493244	-3.43255	6.37345	0	0	0	
+6.8	-0.494113	-3.43665	6.36935	0	0	0	
+6.801	-0.494983	-3.44073	6.36527	0	0	0	
+6.802	-0.495851	-3.44481	6.36119	0	0	0	
+6.803	-0.496719	-3.44887	6.35713	0	0	0	
+6.804	-0.497587	-3.45291	6.35309	0	0	0	
+6.805	-0.498454	-3.45694	6.34906	0	0	0	
+6.806	-0.499321	-3.46096	6.34504	0	0	0	
+6.807	-0.500187	-3.46496	6.34104	0	0	0	
+6.808	-0.501053	-3.46896	6.33704	0	0	0	
+6.809	-0.501918	-3.47293	6.33307	0	0	0	
+6.81	-0.502782	-3.47689	6.32911	0	0	0	
+6.811	-0.503647	-3.48084	6.32516	0	0	0	
+6.812	-0.50451	-3.48478	6.32122	0	0	0	
+6.813	-0.505373	-3.4887	6.3173	0	0	0	
+6.814	-0.506236	-3.4926	6.3134	0	0	0	
+6.815	-0.507098	-3.4965	6.3095	0	0	0	
+6.816	-0.50796	-3.50037	6.30563	0	0	0	
+6.817	-0.508821	-3.50424	6.30176	0	0	0	
+6.818	-0.509682	-3.50809	6.29791	0	0	0	
+6.819	-0.510542	-3.51193	6.29407	0	0	0	
+6.82	-0.511401	-3.51575	6.29025	0	0	0	
+6.821	-0.51226	-3.51956	6.28644	0	0	0	
+6.822	-0.513119	-3.52335	6.28265	0	0	0	
+6.823	-0.513977	-3.52713	6.27887	0	0	0	
+6.824	-0.514835	-3.5309	6.2751	0	0	0	
+6.825	-0.515692	-3.53465	6.27135	0	0	0	
+6.826	-0.516548	-3.53839	6.26761	0	0	0	
+6.827	-0.517404	-3.54211	6.26389	0	0	0	
+6.828	-0.51826	-3.54582	6.26018	0	0	0	
+6.829	-0.519115	-3.54952	6.25648	0	0	0	
+6.83	-0.519969	-3.5532	6.2528	0	0	0	
+6.831	-0.520823	-3.55687	6.24913	0	0	0	
+6.832	-0.521676	-3.56052	6.24548	0	0	0	
+6.833	-0.522529	-3.56416	6.24184	0	0	0	
+6.834	-0.523382	-3.56778	6.23822	0	0	0	
+6.835	-0.524233	-3.57139	6.23461	0	0	0	
+6.836	-0.525085	-3.57499	6.23101	0	0	0	
+6.837	-0.525936	-3.57857	6.22743	0	0	0	
+6.838	-0.526786	-3.58214	6.22386	0	0	0	
+6.839	-0.527636	-3.58569	6.22031	0	0	0	
+6.84	-0.528485	-3.58923	6.21677	0	0	0	
+6.841	-0.529333	-3.59275	6.21325	0	0	0	
+6.842	-0.530182	-3.59626	6.20974	0	0	0	
+6.843	-0.531029	-3.59976	6.20624	0	0	0	
+6.844	-0.531876	-3.60324	6.20276	0	0	0	
+6.845	-0.532723	-3.6067	6.1993	0	0	0	
+6.846	-0.533569	-3.61016	6.19584	0	0	0	
+6.847	-0.534414	-3.61359	6.19241	0	0	0	
+6.848	-0.535259	-3.61702	6.18898	0	0	0	
+6.849	-0.536104	-3.62042	6.18558	0	0	0	
+6.85	-0.536948	-3.62382	6.18218	0	0	0	
+6.851	-0.537791	-3.6272	6.1788	0	0	0	
+6.852	-0.538634	-3.63056	6.17544	0	0	0	
+6.853	-0.539476	-3.63391	6.17209	0	0	0	
+6.854	-0.540318	-3.63725	6.16875	0	0	0	
+6.855	-0.541159	-3.64057	6.16543	0	0	0	
+6.856	-0.542	-3.64388	6.16212	0	0	0	
+6.857	-0.54284	-3.64717	6.15883	0	0	0	
+6.858	-0.543679	-3.65045	6.15555	0	0	0	
+6.859	-0.544518	-3.65371	6.15229	0	0	0	
+6.86	-0.545357	-3.65696	6.14904	0	0	0	
+6.861	-0.546195	-3.6602	6.1458	0	0	0	
+6.862	-0.547032	-3.66342	6.14258	0	0	0	
+6.863	-0.547869	-3.66662	6.13938	0	0	0	
+6.864	-0.548705	-3.66981	6.13619	0	0	0	
+6.865	-0.549541	-3.67299	6.13301	0	0	0	
+6.866	-0.550376	-3.67615	6.12985	0	0	0	
+6.867	-0.551211	-3.67929	6.12671	0	0	0	
+6.868	-0.552045	-3.68242	6.12358	0	0	0	
+6.869	-0.552878	-3.68554	6.12046	0	0	0	
+6.87	-0.553711	-3.68864	6.11736	0	0	0	
+6.871	-0.554544	-3.69173	6.11427	0	0	0	
+6.872	-0.555376	-3.6948	6.1112	0	0	0	
+6.873	-0.556207	-3.69786	6.10814	0	0	0	
+6.874	-0.557038	-3.7009	6.1051	0	0	0	
+6.875	-0.557868	-3.70393	6.10207	0	0	0	
+6.876	-0.558698	-3.70694	6.09906	0	0	0	
+6.877	-0.559527	-3.70994	6.09606	0	0	0	
+6.878	-0.560355	-3.71292	6.09308	0	0	0	
+6.879	-0.561183	-3.71589	6.09011	0	0	0	
+6.88	-0.562011	-3.71885	6.08715	0	0	0	
+6.881	-0.562838	-3.72179	6.08421	0	0	0	
+6.882	-0.563664	-3.72471	6.08129	0	0	0	
+6.883	-0.56449	-3.72762	6.07838	0	0	0	
+6.884	-0.565315	-3.73051	6.07549	0	0	0	
+6.885	-0.566139	-3.73339	6.07261	0	0	0	
+6.886	-0.566963	-3.73626	6.06974	0	0	0	
+6.887	-0.567787	-3.73911	6.06689	0	0	0	
+6.888	-0.56861	-3.74194	6.06406	0	0	0	
+6.889	-0.569432	-3.74476	6.06124	0	0	0	
+6.89	-0.570254	-3.74756	6.05844	0	0	0	
+6.891	-0.571075	-3.75035	6.05565	0	0	0	
+6.892	-0.571896	-3.75313	6.05287	0	0	0	
+6.893	-0.572716	-3.75589	6.05011	0	0	0	
+6.894	-0.573535	-3.75863	6.04737	0	0	0	
+6.895	-0.574354	-3.76136	6.04464	0	0	0	
+6.896	-0.575172	-3.76408	6.04192	0	0	0	
+6.897	-0.57599	-3.76678	6.03922	0	0	0	
+6.898	-0.576807	-3.76946	6.03654	0	0	0	
+6.899	-0.577624	-3.77213	6.03387	0	0	0	
+6.9	-0.57844	-3.77478	6.03122	0	0	0	
+6.901	-0.579255	-3.77742	6.02858	0	0	0	
+6.902	-0.58007	-3.78005	6.02595	0	0	0	
+6.903	-0.580884	-3.78265	6.02335	0	0	0	
+6.904	-0.581698	-3.78525	6.02075	0	0	0	
+6.905	-0.582511	-3.78783	6.01817	0	0	0	
+6.906	-0.583324	-3.79039	6.01561	0	0	0	
+6.907	-0.584136	-3.79294	6.01306	0	0	0	
+6.908	-0.584947	-3.79547	6.01053	0	0	0	
+6.909	-0.585758	-3.79799	6.00801	0	0	0	
+6.91	-0.586568	-3.80049	6.00551	0	0	0	
+6.911	-0.587378	-3.80298	6.00302	0	0	0	
+6.912	-0.588187	-3.80545	6.00055	0	0	0	
+6.913	-0.588995	-3.80791	5.99809	0	0	0	
+6.914	-0.589803	-3.81035	5.99565	0	0	0	
+6.915	-0.59061	-3.81278	5.99322	0	0	0	
+6.916	-0.591417	-3.81519	5.99081	0	0	0	
+6.917	-0.592223	-3.81758	5.98842	0	0	0	
+6.918	-0.593028	-3.81996	5.98604	0	0	0	
+6.919	-0.593833	-3.82233	5.98367	0	0	0	
+6.92	-0.594637	-3.82468	5.98132	0	0	0	
+6.921	-0.595441	-3.82701	5.97899	0	0	0	
+6.922	-0.596244	-3.82933	5.97667	0	0	0	
+6.923	-0.597047	-3.83164	5.97436	0	0	0	
+6.924	-0.597849	-3.83393	5.97207	0	0	0	
+6.925	-0.59865	-3.8362	5.9698	0	0	0	
+6.926	-0.599451	-3.83846	5.96754	0	0	0	
+6.927	-0.600251	-3.8407	5.9653	0	0	0	
+6.928	-0.60105	-3.84293	5.96307	0	0	0	
+6.929	-0.601849	-3.84514	5.96086	0	0	0	
+6.93	-0.602648	-3.84734	5.95866	0	0	0	
+6.931	-0.603445	-3.84952	5.95648	0	0	0	
+6.932	-0.604242	-3.85169	5.95431	0	0	0	
+6.933	-0.605039	-3.85384	5.95216	0	0	0	
+6.934	-0.605835	-3.85597	5.95003	0	0	0	
+6.935	-0.60663	-3.85809	5.94791	0	0	0	
+6.936	-0.607425	-3.8602	5.9458	0	0	0	
+6.937	-0.608219	-3.86228	5.94372	0	0	0	
+6.938	-0.609012	-3.86436	5.94164	0	0	0	
+6.939	-0.609805	-3.86642	5.93958	0	0	0	
+6.94	-0.610597	-3.86846	5.93754	0	0	0	
+6.941	-0.611389	-3.87048	5.93552	0	0	0	
+6.942	-0.61218	-3.8725	5.9335	0	0	0	
+6.943	-0.61297	-3.87449	5.93151	0	0	0	
+6.944	-0.61376	-3.87647	5.92953	0	0	0	
+6.945	-0.614549	-3.87844	5.92756	0	0	0	
+6.946	-0.615338	-3.88039	5.92561	0	0	0	
+6.947	-0.616126	-3.88232	5.92368	0	0	0	
+6.948	-0.616913	-3.88424	5.92176	0	0	0	
+6.949	-0.6177	-3.88614	5.91986	0	0	0	
+6.95	-0.618486	-3.88803	5.91797	0	0	0	
+6.951	-0.619272	-3.8899	5.9161	0	0	0	
+6.952	-0.620056	-3.89176	5.91424	0	0	0	
+6.953	-0.620841	-3.8936	5.9124	0	0	0	
+6.954	-0.621624	-3.89542	5.91058	0	0	0	
+6.955	-0.622407	-3.89723	5.90877	0	0	0	
+6.956	-0.62319	-3.89903	5.90697	0	0	0	
+6.957	-0.623972	-3.90081	5.90519	0	0	0	
+6.958	-0.624753	-3.90257	5.90343	0	0	0	
+6.959	-0.625533	-3.90432	5.90168	0	0	0	
+6.96	-0.626313	-3.90605	5.89995	0	0	0	
+6.961	-0.627092	-3.90776	5.89824	0	0	0	
+6.962	-0.627871	-3.90946	5.89654	0	0	0	
+6.963	-0.628649	-3.91115	5.89485	0	0	0	
+6.964	-0.629426	-3.91282	5.89318	0	0	0	
+6.965	-0.630203	-3.91447	5.89153	0	0	0	
+6.966	-0.630979	-3.91611	5.88989	0	0	0	
+6.967	-0.631755	-3.91773	5.88827	0	0	0	
+6.968	-0.632529	-3.91934	5.88666	0	0	0	
+6.969	-0.633304	-3.92093	5.88507	0	0	0	
+6.97	-0.634077	-3.9225	5.8835	0	0	0	
+6.971	-0.63485	-3.92406	5.88194	0	0	0	
+6.972	-0.635623	-3.9256	5.8804	0	0	0	
+6.973	-0.636394	-3.92713	5.87887	0	0	0	
+6.974	-0.637165	-3.92864	5.87736	0	0	0	
+6.975	-0.637936	-3.93014	5.87586	0	0	0	
+6.976	-0.638705	-3.93162	5.87438	0	0	0	
+6.977	-0.639475	-3.93309	5.87291	0	0	0	
+6.978	-0.640243	-3.93454	5.87146	0	0	0	
+6.979	-0.641011	-3.93597	5.87003	0	0	0	
+6.98	-0.641778	-3.93739	5.86861	0	0	0	
+6.981	-0.642545	-3.93879	5.86721	0	0	0	
+6.982	-0.643311	-3.94018	5.86582	0	0	0	
+6.983	-0.644076	-3.94155	5.86445	0	0	0	
+6.984	-0.644841	-3.9429	5.8631	0	0	0	
+6.985	-0.645605	-3.94424	5.86176	0	0	0	
+6.986	-0.646368	-3.94556	5.86044	0	0	0	
+6.987	-0.647131	-3.94687	5.85913	0	0	0	
+6.988	-0.647893	-3.94816	5.85784	0	0	0	
+6.989	-0.648654	-3.94944	5.85656	0	0	0	
+6.99	-0.649415	-3.9507	5.8553	0	0	0	
+6.991	-0.650175	-3.95194	5.85406	0	0	0	
+6.992	-0.650934	-3.95317	5.85283	0	0	0	
+6.993	-0.651693	-3.95438	5.85162	0	0	0	
+6.994	-0.652451	-3.95558	5.85042	0	0	0	
+6.995	-0.653209	-3.95676	5.84924	0	0	0	
+6.996	-0.653966	-3.95793	5.84807	0	0	0	
+6.997	-0.654722	-3.95908	5.84692	0	0	0	
+6.998	-0.655477	-3.96021	5.84579	0	0	0	
+6.999	-0.656232	-3.96133	5.84467	0	0	0	
+7	-0.656987	-3.96243	5.84357	0	0	0	
+7.001	-0.65774	-3.96352	5.84248	0	0	0	
+7.002	-0.658493	-3.96459	5.84141	0	0	0	
+7.003	-0.659245	-3.96564	5.84036	0	0	0	
+7.004	-0.659997	-3.96668	5.83932	0	0	0	
+7.005	-0.660748	-3.9677	5.8383	0	0	0	
+7.006	-0.661498	-3.96871	5.83729	0	0	0	
+7.007	-0.662248	-3.9697	5.8363	0	0	0	
+7.008	-0.662997	-3.97067	5.83533	0	0	0	
+7.009	-0.663745	-3.97163	5.83437	0	0	0	
+7.01	-0.664493	-3.97258	5.83342	0	0	0	
+7.011	-0.66524	-3.9735	5.8325	0	0	0	
+7.012	-0.665986	-3.97441	5.83159	0	0	0	
+7.013	-0.666732	-3.97531	5.83069	0	0	0	
+7.014	-0.667477	-3.97619	5.82981	0	0	0	
+7.015	-0.668221	-3.97705	5.82895	0	0	0	
+7.016	-0.668964	-3.9779	5.8281	0	0	0	
+7.017	-0.669707	-3.97873	5.82727	0	0	0	
+7.018	-0.67045	-3.97955	5.82645	0	0	0	
+7.019	-0.671191	-3.98035	5.82565	0	0	0	
+7.02	-0.671932	-3.98113	5.82487	0	0	0	
+7.021	-0.672673	-3.9819	5.8241	0	0	0	
+7.022	-0.673412	-3.98265	5.82335	0	0	0	
+7.023	-0.674151	-3.98339	5.82261	0	0	0	
+7.024	-0.674889	-3.98411	5.82189	0	0	0	
+7.025	-0.675627	-3.98481	5.82119	0	0	0	
+7.026	-0.676364	-3.9855	5.8205	0	0	0	
+7.027	-0.6771	-3.98617	5.81983	0	0	0	
+7.028	-0.677836	-3.98683	5.81917	0	0	0	
+7.029	-0.67857	-3.98747	5.81853	0	0	0	
+7.03	-0.679305	-3.9881	5.8179	0	0	0	
+7.031	-0.680038	-3.98871	5.81729	0	0	0	
+7.032	-0.680771	-3.9893	5.8167	0	0	0	
+7.033	-0.681503	-3.98987	5.81613	0	0	0	
+7.034	-0.682235	-3.99044	5.81556	0	0	0	
+7.035	-0.682965	-3.99098	5.81502	0	0	0	
+7.036	-0.683696	-3.99151	5.81449	0	0	0	
+7.037	-0.684425	-3.99202	5.81398	0	0	0	
+7.038	-0.685154	-3.99252	5.81348	0	0	0	
+7.039	-0.685882	-3.993	5.813	0	0	0	
+7.04	-0.686609	-3.99347	5.81253	0	0	0	
+7.041	-0.687336	-3.99391	5.81209	0	0	0	
+7.042	-0.688062	-3.99435	5.81165	0	0	0	
+7.043	-0.688787	-3.99477	5.81123	0	0	0	
+7.044	-0.689512	-3.99517	5.81083	0	0	0	
+7.045	-0.690236	-3.99555	5.81045	0	0	0	
+7.046	-0.690959	-3.99592	5.81008	0	0	0	
+7.047	-0.691681	-3.99627	5.80973	0	0	0	
+7.048	-0.692403	-3.99661	5.80939	0	0	0	
+7.049	-0.693124	-3.99693	5.80907	0	0	0	
+7.05	-0.693845	-3.99724	5.80876	0	0	0	
+7.051	-0.694565	-3.99753	5.80847	0	0	0	
+7.052	-0.695284	-3.9978	5.8082	0	0	0	
+7.053	-0.696002	-3.99806	5.80794	0	0	0	
+7.054	-0.69672	-3.9983	5.8077	0	0	0	
+7.055	-0.697437	-3.99852	5.80748	0	0	0	
+7.056	-0.698153	-3.99873	5.80727	0	0	0	
+7.057	-0.698869	-3.99893	5.80707	0	0	0	
+7.058	-0.699584	-3.9991	5.8069	0	0	0	
+7.059	-0.700298	-3.99927	5.80673	0	0	0	
+7.06	-0.701011	-3.99941	5.80659	0	0	0	
+7.061	-0.701724	-3.99954	5.80646	0	0	0	
+7.062	-0.702436	-3.99965	5.80635	0	0	0	
+7.063	-0.703148	-3.99975	5.80625	0	0	0	
+7.064	-0.703858	-3.99983	5.80617	0	0	0	
+7.065	-0.704568	-3.9999	5.8061	0	0	0	
+7.066	-0.705278	-3.99995	5.80605	0	0	0	
+7.067	-0.705986	-3.99998	5.80602	0	0	0	
+7.068	-0.706694	-4	5.806	0	0	0	
+7.069	-0.707401	-4	5.806	0	0	0	
+7.07	-0.708108	-3.99998	5.80602	0	0	0	
+7.071	-0.708813	-3.99995	5.80605	0	0	0	
+7.072	-0.709519	-3.99991	5.80609	0	0	0	
+7.073	-0.710223	-3.99984	5.80616	0	0	0	
+7.074	-0.710926	-3.99977	5.80623	0	0	0	
+7.075	-0.711629	-3.99967	5.80633	0	0	0	
+7.076	-0.712332	-3.99956	5.80644	0	0	0	
+7.077	-0.713033	-3.99943	5.80657	0	0	0	
+7.078	-0.713734	-3.99929	5.80671	0	0	0	
+7.079	-0.714434	-3.99913	5.80687	0	0	0	
+7.08	-0.715133	-3.99896	5.80704	0	0	0	
+7.081	-0.715832	-3.99877	5.80723	0	0	0	
+7.082	-0.71653	-3.99856	5.80744	0	0	0	
+7.083	-0.717227	-3.99834	5.80766	0	0	0	
+7.084	-0.717923	-3.9981	5.8079	0	0	0	
+7.085	-0.718619	-3.99784	5.80816	0	0	0	
+7.086	-0.719314	-3.99757	5.80843	0	0	0	
+7.087	-0.720009	-3.99729	5.80871	0	0	0	
+7.088	-0.720702	-3.99698	5.80902	0	0	0	
+7.089	-0.721395	-3.99667	5.80933	0	0	0	
+7.09	-0.722087	-3.99633	5.80967	0	0	0	
+7.091	-0.722779	-3.99598	5.81002	0	0	0	
+7.092	-0.723469	-3.99561	5.81039	0	0	0	
+7.093	-0.724159	-3.99523	5.81077	0	0	0	
+7.094	-0.724849	-3.99483	5.81117	0	0	0	
+7.095	-0.725537	-3.99442	5.81158	0	0	0	
+7.096	-0.726225	-3.99399	5.81201	0	0	0	
+7.097	-0.726912	-3.99354	5.81246	0	0	0	
+7.098	-0.727598	-3.99308	5.81292	0	0	0	
+7.099	-0.728284	-3.9926	5.8134	0	0	0	
+7.1	-0.728969	-3.99211	5.81389	0	0	0	
+7.101	-0.729653	-3.9916	5.8144	0	0	0	
+7.102	-0.730337	-3.99107	5.81493	0	0	0	
+7.103	-0.731019	-3.99053	5.81547	0	0	0	
+7.104	-0.731701	-3.98997	5.81603	0	0	0	
+7.105	-0.732383	-3.9894	5.8166	0	0	0	
+7.106	-0.733063	-3.98881	5.81719	0	0	0	
+7.107	-0.733743	-3.9882	5.8178	0	0	0	
+7.108	-0.734422	-3.98758	5.81842	0	0	0	
+7.109	-0.7351	-3.98694	5.81906	0	0	0	
+7.11	-0.735778	-3.98629	5.81971	0	0	0	
+7.111	-0.736455	-3.98562	5.82038	0	0	0	
+7.112	-0.737131	-3.98493	5.82107	0	0	0	
+7.113	-0.737806	-3.98423	5.82177	0	0	0	
+7.114	-0.738481	-3.98351	5.82249	0	0	0	
+7.115	-0.739155	-3.98278	5.82322	0	0	0	
+7.116	-0.739828	-3.98203	5.82397	0	0	0	
+7.117	-0.7405	-3.98126	5.82474	0	0	0	
+7.118	-0.741172	-3.98048	5.82552	0	0	0	
+7.119	-0.741843	-3.97968	5.82632	0	0	0	
+7.12	-0.742513	-3.97887	5.82713	0	0	0	
+7.121	-0.743183	-3.97804	5.82796	0	0	0	
+7.122	-0.743851	-3.9772	5.8288	0	0	0	
+7.123	-0.744519	-3.97633	5.82967	0	0	0	
+7.124	-0.745187	-3.97546	5.83054	0	0	0	
+7.125	-0.745853	-3.97456	5.83144	0	0	0	
+7.126	-0.746519	-3.97366	5.83234	0	0	0	
+7.127	-0.747184	-3.97273	5.83327	0	0	0	
+7.128	-0.747848	-3.97179	5.83421	0	0	0	
+7.129	-0.748512	-3.97083	5.83517	0	0	0	
+7.13	-0.749174	-3.96986	5.83614	0	0	0	
+7.131	-0.749836	-3.96887	5.83713	0	0	0	
+7.132	-0.750498	-3.96787	5.83813	0	0	0	
+7.133	-0.751158	-3.96685	5.83915	0	0	0	
+7.134	-0.751818	-3.96581	5.84019	0	0	0	
+7.135	-0.752477	-3.96476	5.84124	0	0	0	
+7.136	-0.753135	-3.9637	5.8423	0	0	0	
+7.137	-0.753793	-3.96261	5.84339	0	0	0	
+7.138	-0.754449	-3.96151	5.84449	0	0	0	
+7.139	-0.755105	-3.9604	5.8456	0	0	0	
+7.14	-0.755761	-3.95927	5.84673	0	0	0	
+7.141	-0.756415	-3.95812	5.84788	0	0	0	
+7.142	-0.757069	-3.95696	5.84904	0	0	0	
+7.143	-0.757722	-3.95578	5.85022	0	0	0	
+7.144	-0.758374	-3.95458	5.85142	0	0	0	
+7.145	-0.759025	-3.95337	5.85263	0	0	0	
+7.146	-0.759676	-3.95215	5.85385	0	0	0	
+7.147	-0.760326	-3.95091	5.85509	0	0	0	
+7.148	-0.760975	-3.94965	5.85635	0	0	0	
+7.149	-0.761623	-3.94838	5.85762	0	0	0	
+7.15	-0.762271	-3.94709	5.85891	0	0	0	
+7.151	-0.762918	-3.94578	5.86022	0	0	0	
+7.152	-0.763564	-3.94446	5.86154	0	0	0	
+7.153	-0.764209	-3.94313	5.86287	0	0	0	
+7.154	-0.764854	-3.94177	5.86423	0	0	0	
+7.155	-0.765498	-3.94041	5.86559	0	0	0	
+7.156	-0.766141	-3.93902	5.86698	0	0	0	
+7.157	-0.766783	-3.93762	5.86838	0	0	0	
+7.158	-0.767425	-3.93621	5.86979	0	0	0	
+7.159	-0.768065	-3.93478	5.87122	0	0	0	
+7.16	-0.768705	-3.93333	5.87267	0	0	0	
+7.161	-0.769345	-3.93187	5.87413	0	0	0	
+7.162	-0.769983	-3.93039	5.87561	0	0	0	
+7.163	-0.770621	-3.9289	5.8771	0	0	0	
+7.164	-0.771258	-3.92739	5.87861	0	0	0	
+7.165	-0.771894	-3.92586	5.88014	0	0	0	
+7.166	-0.772529	-3.92432	5.88168	0	0	0	
+7.167	-0.773164	-3.92276	5.88324	0	0	0	
+7.168	-0.773798	-3.92119	5.88481	0	0	0	
+7.169	-0.774431	-3.9196	5.8864	0	0	0	
+7.17	-0.775063	-3.918	5.888	0	0	0	
+7.171	-0.775694	-3.91638	5.88962	0	0	0	
+7.172	-0.776325	-3.91474	5.89126	0	0	0	
+7.173	-0.776955	-3.91309	5.89291	0	0	0	
+7.174	-0.777584	-3.91143	5.89457	0	0	0	
+7.175	-0.778213	-3.90975	5.89625	0	0	0	
+7.176	-0.77884	-3.90805	5.89795	0	0	0	
+7.177	-0.779467	-3.90633	5.89967	0	0	0	
+7.178	-0.780093	-3.90461	5.90139	0	0	0	
+7.179	-0.780718	-3.90286	5.90314	0	0	0	
+7.18	-0.781343	-3.9011	5.9049	0	0	0	
+7.181	-0.781967	-3.89933	5.90667	0	0	0	
+7.182	-0.78259	-3.89753	5.90847	0	0	0	
+7.183	-0.783212	-3.89573	5.91027	0	0	0	
+7.184	-0.783833	-3.8939	5.9121	0	0	0	
+7.185	-0.784454	-3.89207	5.91393	0	0	0	
+7.186	-0.785073	-3.89021	5.91579	0	0	0	
+7.187	-0.785692	-3.88834	5.91766	0	0	0	
+7.188	-0.786311	-3.88646	5.91954	0	0	0	
+7.189	-0.786928	-3.88456	5.92144	0	0	0	
+7.19	-0.787545	-3.88264	5.92336	0	0	0	
+7.191	-0.788161	-3.88071	5.92529	0	0	0	
+7.192	-0.788776	-3.87876	5.92724	0	0	0	
+7.193	-0.78939	-3.8768	5.9292	0	0	0	
+7.194	-0.790003	-3.87482	5.93118	0	0	0	
+7.195	-0.790616	-3.87283	5.93317	0	0	0	
+7.196	-0.791228	-3.87082	5.93518	0	0	0	
+7.197	-0.791839	-3.8688	5.9372	0	0	0	
+7.198	-0.79245	-3.86676	5.93924	0	0	0	
+7.199	-0.793059	-3.8647	5.9413	0	0	0	
+7.2	-0.793668	-3.86263	5.94337	0	0	0	
+7.201	-0.794276	-3.86054	5.94546	0	0	0	
+7.202	-0.794883	-3.85844	5.94756	0	0	0	
+7.203	-0.795489	-3.85633	5.94967	0	0	0	
+7.204	-0.796095	-3.85419	5.95181	0	0	0	
+7.205	-0.7967	-3.85205	5.95395	0	0	0	
+7.206	-0.797304	-3.84988	5.95612	0	0	0	
+7.207	-0.797907	-3.8477	5.9583	0	0	0	
+7.208	-0.798509	-3.84551	5.96049	0	0	0	
+7.209	-0.799111	-3.8433	5.9627	0	0	0	
+7.21	-0.799712	-3.84107	5.96493	0	0	0	
+7.211	-0.800312	-3.83883	5.96717	0	0	0	
+7.212	-0.800911	-3.83658	5.96942	0	0	0	
+7.213	-0.801509	-3.83431	5.97169	0	0	0	
+7.214	-0.802107	-3.83202	5.97398	0	0	0	
+7.215	-0.802704	-3.82972	5.97628	0	0	0	
+7.216	-0.803299	-3.8274	5.9786	0	0	0	
+7.217	-0.803895	-3.82507	5.98093	0	0	0	
+7.218	-0.804489	-3.82272	5.98328	0	0	0	
+7.219	-0.805083	-3.82036	5.98564	0	0	0	
+7.22	-0.805675	-3.81798	5.98802	0	0	0	
+7.221	-0.806267	-3.81559	5.99041	0	0	0	
+7.222	-0.806858	-3.81318	5.99282	0	0	0	
+7.223	-0.807449	-3.81076	5.99524	0	0	0	
+7.224	-0.808038	-3.80832	5.99768	0	0	0	
+7.225	-0.808627	-3.80586	6.00014	0	0	0	
+7.226	-0.809215	-3.80339	6.00261	0	0	0	
+7.227	-0.809802	-3.80091	6.00509	0	0	0	
+7.228	-0.810388	-3.79841	6.00759	0	0	0	
+7.229	-0.810974	-3.79589	6.01011	0	0	0	
+7.23	-0.811559	-3.79336	6.01264	0	0	0	
+7.231	-0.812142	-3.79082	6.01518	0	0	0	
+7.232	-0.812725	-3.78826	6.01774	0	0	0	
+7.233	-0.813308	-3.78568	6.02032	0	0	0	
+7.234	-0.813889	-3.78309	6.02291	0	0	0	
+7.235	-0.81447	-3.78048	6.02552	0	0	0	
+7.236	-0.81505	-3.77786	6.02814	0	0	0	
+7.237	-0.815629	-3.77522	6.03078	0	0	0	
+7.238	-0.816207	-3.77257	6.03343	0	0	0	
+7.239	-0.816784	-3.76991	6.03609	0	0	0	
+7.24	-0.817361	-3.76722	6.03878	0	0	0	
+7.241	-0.817936	-3.76453	6.04147	0	0	0	
+7.242	-0.818511	-3.76182	6.04418	0	0	0	
+7.243	-0.819085	-3.75909	6.04691	0	0	0	
+7.244	-0.819659	-3.75635	6.04965	0	0	0	
+7.245	-0.820231	-3.75359	6.05241	0	0	0	
+7.246	-0.820803	-3.75082	6.05518	0	0	0	
+7.247	-0.821373	-3.74803	6.05797	0	0	0	
+7.248	-0.821943	-3.74523	6.06077	0	0	0	
+7.249	-0.822513	-3.74241	6.06359	0	0	0	
+7.25	-0.823081	-3.73958	6.06642	0	0	0	
+7.251	-0.823648	-3.73673	6.06927	0	0	0	
+7.252	-0.824215	-3.73387	6.07213	0	0	0	
+7.253	-0.824781	-3.73099	6.07501	0	0	0	
+7.254	-0.825346	-3.7281	6.0779	0	0	0	
+7.255	-0.82591	-3.7252	6.0808	0	0	0	
+7.256	-0.826474	-3.72228	6.08372	0	0	0	
+7.257	-0.827036	-3.71934	6.08666	0	0	0	
+7.258	-0.827598	-3.71639	6.08961	0	0	0	
+7.259	-0.828159	-3.71342	6.09258	0	0	0	
+7.26	-0.828719	-3.71044	6.09556	0	0	0	
+7.261	-0.829278	-3.70744	6.09856	0	0	0	
+7.262	-0.829837	-3.70443	6.10157	0	0	0	
+7.263	-0.830394	-3.70141	6.10459	0	0	0	
+7.264	-0.830951	-3.69837	6.10763	0	0	0	
+7.265	-0.831507	-3.69531	6.11069	0	0	0	
+7.266	-0.832062	-3.69224	6.11376	0	0	0	
+7.267	-0.832616	-3.68916	6.11684	0	0	0	
+7.268	-0.83317	-3.68606	6.11994	0	0	0	
+7.269	-0.833722	-3.68295	6.12305	0	0	0	
+7.27	-0.834274	-3.67982	6.12618	0	0	0	
+7.271	-0.834825	-3.67667	6.12933	0	0	0	
+7.272	-0.835375	-3.67351	6.13249	0	0	0	
+7.273	-0.835924	-3.67034	6.13566	0	0	0	
+7.274	-0.836473	-3.66715	6.13885	0	0	0	
+7.275	-0.83702	-3.66395	6.14205	0	0	0	
+7.276	-0.837567	-3.66073	6.14527	0	0	0	
+7.277	-0.838113	-3.6575	6.1485	0	0	0	
+7.278	-0.838658	-3.65426	6.15174	0	0	0	
+7.279	-0.839202	-3.651	6.155	0	0	0	
+7.28	-0.839746	-3.64772	6.15828	0	0	0	
+7.281	-0.840288	-3.64443	6.16157	0	0	0	
+7.282	-0.84083	-3.64113	6.16487	0	0	0	
+7.283	-0.841371	-3.63781	6.16819	0	0	0	
+7.284	-0.841911	-3.63447	6.17153	0	0	0	
+7.285	-0.84245	-3.63112	6.17488	0	0	0	
+7.286	-0.842988	-3.62776	6.17824	0	0	0	
+7.287	-0.843526	-3.62438	6.18162	0	0	0	
+7.288	-0.844063	-3.62099	6.18501	0	0	0	
+7.289	-0.844598	-3.61759	6.18841	0	0	0	
+7.29	-0.845133	-3.61417	6.19183	0	0	0	
+7.291	-0.845668	-3.61073	6.19527	0	0	0	
+7.292	-0.846201	-3.60728	6.19872	0	0	0	
+7.293	-0.846733	-3.60382	6.20218	0	0	0	
+7.294	-0.847265	-3.60034	6.20566	0	0	0	
+7.295	-0.847796	-3.59684	6.20916	0	0	0	
+7.296	-0.848326	-3.59334	6.21266	0	0	0	
+7.297	-0.848855	-3.58982	6.21618	0	0	0	
+7.298	-0.849383	-3.58628	6.21972	0	0	0	
+7.299	-0.84991	-3.58273	6.22327	0	0	0	
+7.3	-0.850437	-3.57916	6.22684	0	0	0	
+7.301	-0.850962	-3.57559	6.23041	0	0	0	
+7.302	-0.851487	-3.57199	6.23401	0	0	0	
+7.303	-0.852011	-3.56838	6.23762	0	0	0	
+7.304	-0.852534	-3.56476	6.24124	0	0	0	
+7.305	-0.853056	-3.56113	6.24487	0	0	0	
+7.306	-0.853578	-3.55748	6.24852	0	0	0	
+7.307	-0.854098	-3.55381	6.25219	0	0	0	
+7.308	-0.854618	-3.55013	6.25587	0	0	0	
+7.309	-0.855137	-3.54644	6.25956	0	0	0	
+7.31	-0.855655	-3.54273	6.26327	0	0	0	
+7.311	-0.856172	-3.53901	6.26699	0	0	0	
+7.312	-0.856688	-3.53528	6.27072	0	0	0	
+7.313	-0.857204	-3.53153	6.27447	0	0	0	
+7.314	-0.857718	-3.52776	6.27824	0	0	0	
+7.315	-0.858232	-3.52398	6.28202	0	0	0	
+7.316	-0.858745	-3.52019	6.28581	0	0	0	
+7.317	-0.859257	-3.51639	6.28961	0	0	0	
+7.318	-0.859768	-3.51257	6.29343	0	0	0	
+7.319	-0.860278	-3.50873	6.29727	0	0	0	
+7.32	-0.860787	-3.50488	6.30112	0	0	0	
+7.321	-0.861296	-3.50102	6.30498	0	0	0	
+7.322	-0.861804	-3.49714	6.30886	0	0	0	
+7.323	-0.86231	-3.49325	6.31275	0	0	0	
+7.324	-0.862816	-3.48935	6.31665	0	0	0	
+7.325	-0.863321	-3.48543	6.32057	0	0	0	
+7.326	-0.863826	-3.4815	6.3245	0	0	0	
+7.327	-0.864329	-3.47755	6.32845	0	0	0	
+7.328	-0.864832	-3.47359	6.33241	0	0	0	
+7.329	-0.865333	-3.46962	6.33638	0	0	0	
+7.33	-0.865834	-3.46563	6.34037	0	0	0	
+7.331	-0.866334	-3.46163	6.34437	0	0	0	
+7.332	-0.866833	-3.45761	6.34839	0	0	0	
+7.333	-0.867331	-3.45359	6.35241	0	0	0	
+7.334	-0.867828	-3.44954	6.35646	0	0	0	
+7.335	-0.868325	-3.44549	6.36051	0	0	0	
+7.336	-0.86882	-3.44141	6.36459	0	0	0	
+7.337	-0.869315	-3.43733	6.36867	0	0	0	
+7.338	-0.869809	-3.43323	6.37277	0	0	0	
+7.339	-0.870302	-3.42912	6.37688	0	0	0	
+7.34	-0.870794	-3.42499	6.38101	0	0	0	
+7.341	-0.871285	-3.42086	6.38514	0	0	0	
+7.342	-0.871775	-3.4167	6.3893	0	0	0	
+7.343	-0.872265	-3.41254	6.39346	0	0	0	
+7.344	-0.872753	-3.40836	6.39764	0	0	0	
+7.345	-0.873241	-3.40416	6.40184	0	0	0	
+7.346	-0.873728	-3.39995	6.40605	0	0	0	
+7.347	-0.874214	-3.39573	6.41027	0	0	0	
+7.348	-0.874699	-3.3915	6.4145	0	0	0	
+7.349	-0.875183	-3.38725	6.41875	0	0	0	
+7.35	-0.875667	-3.38299	6.42301	0	0	0	
+7.351	-0.876149	-3.37871	6.42729	0	0	0	
+7.352	-0.876631	-3.37442	6.43158	0	0	0	
+7.353	-0.877112	-3.37012	6.43588	0	0	0	
+7.354	-0.877591	-3.3658	6.4402	0	0	0	
+7.355	-0.87807	-3.36148	6.44452	0	0	0	
+7.356	-0.878548	-3.35713	6.44887	0	0	0	
+7.357	-0.879026	-3.35278	6.45322	0	0	0	
+7.358	-0.879502	-3.34841	6.45759	0	0	0	
+7.359	-0.879977	-3.34402	6.46198	0	0	0	
+7.36	-0.880452	-3.33963	6.46637	0	0	0	
+7.361	-0.880926	-3.33522	6.47078	0	0	0	
+7.362	-0.881399	-3.33079	6.47521	0	0	0	
+7.363	-0.88187	-3.32636	6.47964	0	0	0	
+7.364	-0.882342	-3.32191	6.48409	0	0	0	
+7.365	-0.882812	-3.31744	6.48856	0	0	0	
+7.366	-0.883281	-3.31297	6.49303	0	0	0	
+7.367	-0.883749	-3.30848	6.49752	0	0	0	
+7.368	-0.884217	-3.30398	6.50202	0	0	0	
+7.369	-0.884684	-3.29946	6.50654	0	0	0	
+7.37	-0.885149	-3.29493	6.51107	0	0	0	
+7.371	-0.885614	-3.29039	6.51561	0	0	0	
+7.372	-0.886078	-3.28583	6.52017	0	0	0	
+7.373	-0.886541	-3.28126	6.52474	0	0	0	
+7.374	-0.887003	-3.27668	6.52932	0	0	0	
+7.375	-0.887465	-3.27209	6.53391	0	0	0	
+7.376	-0.887925	-3.26748	6.53852	0	0	0	
+7.377	-0.888385	-3.26286	6.54314	0	0	0	
+7.378	-0.888843	-3.25822	6.54778	0	0	0	
+7.379	-0.889301	-3.25358	6.55242	0	0	0	
+7.38	-0.889758	-3.24892	6.55708	0	0	0	
+7.381	-0.890214	-3.24424	6.56176	0	0	0	
+7.382	-0.890669	-3.23956	6.56644	0	0	0	
+7.383	-0.891123	-3.23486	6.57114	0	0	0	
+7.384	-0.891577	-3.23015	6.57585	0	0	0	
+7.385	-0.892029	-3.22542	6.58058	0	0	0	
+7.386	-0.892481	-3.22068	6.58532	0	0	0	
+7.387	-0.892931	-3.21593	6.59007	0	0	0	
+7.388	-0.893381	-3.21117	6.59483	0	0	0	
+7.389	-0.89383	-3.20639	6.59961	0	0	0	
+7.39	-0.894278	-3.2016	6.6044	0	0	0	
+7.391	-0.894725	-3.1968	6.6092	0	0	0	
+7.392	-0.895171	-3.19199	6.61401	0	0	0	
+7.393	-0.895616	-3.18716	6.61884	0	0	0	
+7.394	-0.896061	-3.18232	6.62368	0	0	0	
+7.395	-0.896504	-3.17746	6.62854	0	0	0	
+7.396	-0.896947	-3.1726	6.6334	0	0	0	
+7.397	-0.897388	-3.16772	6.63828	0	0	0	
+7.398	-0.897829	-3.16283	6.64317	0	0	0	
+7.399	-0.898269	-3.15792	6.64808	0	0	0	
+7.4	-0.898708	-3.15301	6.65299	0	0	0	
+7.401	-0.899146	-3.14808	6.65792	0	0	0	
+7.402	-0.899583	-3.14314	6.66286	0	0	0	
+7.403	-0.90002	-3.13818	6.66782	0	0	0	
+7.404	-0.900455	-3.13322	6.67278	0	0	0	
+7.405	-0.90089	-3.12824	6.67776	0	0	0	
+7.406	-0.901323	-3.12325	6.68275	0	0	0	
+7.407	-0.901756	-3.11824	6.68776	0	0	0	
+7.408	-0.902188	-3.11322	6.69278	0	0	0	
+7.409	-0.902619	-3.10819	6.69781	0	0	0	
+7.41	-0.903049	-3.10315	6.70285	0	0	0	
+7.411	-0.903478	-3.0981	6.7079	0	0	0	
+7.412	-0.903906	-3.09303	6.71297	0	0	0	
+7.413	-0.904333	-3.08795	6.71805	0	0	0	
+7.414	-0.904759	-3.08286	6.72314	0	0	0	
+7.415	-0.905185	-3.07776	6.72824	0	0	0	
+7.416	-0.90561	-3.07264	6.73336	0	0	0	
+7.417	-0.906033	-3.06751	6.73849	0	0	0	
+7.418	-0.906456	-3.06237	6.74363	0	0	0	
+7.419	-0.906878	-3.05722	6.74878	0	0	0	
+7.42	-0.907299	-3.05206	6.75394	0	0	0	
+7.421	-0.907719	-3.04688	6.75912	0	0	0	
+7.422	-0.908138	-3.04169	6.76431	0	0	0	
+7.423	-0.908556	-3.03649	6.76951	0	0	0	
+7.424	-0.908973	-3.03127	6.77473	0	0	0	
+7.425	-0.90939	-3.02605	6.77995	0	0	0	
+7.426	-0.909805	-3.02081	6.78519	0	0	0	
+7.427	-0.91022	-3.01556	6.79044	0	0	0	
+7.428	-0.910634	-3.0103	6.7957	0	0	0	
+7.429	-0.911046	-3.00502	6.80098	0	0	0	
+7.43	-0.911458	-2.99974	6.80626	0	0	0	
+7.431	-0.911869	-2.99444	6.81156	0	0	0	
+7.432	-0.912279	-2.98913	6.81687	0	0	0	
+7.433	-0.912688	-2.98381	6.82219	0	0	0	
+7.434	-0.913096	-2.97847	6.82753	0	0	0	
+7.435	-0.913504	-2.97313	6.83287	0	0	0	
+7.436	-0.91391	-2.96777	6.83823	0	0	0	
+7.437	-0.914316	-2.9624	6.8436	0	0	0	
+7.438	-0.91472	-2.95702	6.84898	0	0	0	
+7.439	-0.915124	-2.95163	6.85437	0	0	0	
+7.44	-0.915526	-2.94622	6.85978	0	0	0	
+7.441	-0.915928	-2.9408	6.8652	0	0	0	
+7.442	-0.916329	-2.93538	6.87062	0	0	0	
+7.443	-0.916729	-2.92994	6.87606	0	0	0	
+7.444	-0.917128	-2.92448	6.88152	0	0	0	
+7.445	-0.917526	-2.91902	6.88698	0	0	0	
+7.446	-0.917923	-2.91354	6.89246	0	0	0	
+7.447	-0.91832	-2.90806	6.89794	0	0	0	
+7.448	-0.918715	-2.90256	6.90344	0	0	0	
+7.449	-0.91911	-2.89705	6.90895	0	0	0	
+7.45	-0.919503	-2.89153	6.91447	0	0	0	
+7.451	-0.919896	-2.88599	6.92001	0	0	0	
+7.452	-0.920288	-2.88045	6.92555	0	0	0	
+7.453	-0.920678	-2.87489	6.93111	0	0	0	
+7.454	-0.921068	-2.86932	6.93668	0	0	0	
+7.455	-0.921457	-2.86374	6.94226	0	0	0	
+7.456	-0.921845	-2.85815	6.94785	0	0	0	
+7.457	-0.922232	-2.85255	6.95345	0	0	0	
+7.458	-0.922618	-2.84693	6.95907	0	0	0	
+7.459	-0.923004	-2.84131	6.96469	0	0	0	
+7.46	-0.923388	-2.83567	6.97033	0	0	0	
+7.461	-0.923771	-2.83003	6.97597	0	0	0	
+7.462	-0.924154	-2.82437	6.98163	0	0	0	
+7.463	-0.924535	-2.8187	6.9873	0	0	0	
+7.464	-0.924916	-2.81301	6.99299	0	0	0	
+7.465	-0.925296	-2.80732	6.99868	0	0	0	
+7.466	-0.925675	-2.80162	7.00438	0	0	0	
+7.467	-0.926052	-2.7959	7.0101	0	0	0	
+7.468	-0.926429	-2.79017	7.01583	0	0	0	
+7.469	-0.926805	-2.78444	7.02156	0	0	0	
+7.47	-0.92718	-2.77869	7.02731	0	0	0	
+7.471	-0.927555	-2.77293	7.03307	0	0	0	
+7.472	-0.927928	-2.76715	7.03885	0	0	0	
+7.473	-0.9283	-2.76137	7.04463	0	0	0	
+7.474	-0.928671	-2.75558	7.05042	0	0	0	
+7.475	-0.929042	-2.74977	7.05623	0	0	0	
+7.476	-0.929411	-2.74396	7.06204	0	0	0	
+7.477	-0.92978	-2.73813	7.06787	0	0	0	
+7.478	-0.930148	-2.7323	7.0737	0	0	0	
+7.479	-0.930514	-2.72645	7.07955	0	0	0	
+7.48	-0.93088	-2.72059	7.08541	0	0	0	
+7.481	-0.931245	-2.71472	7.09128	0	0	0	
+7.482	-0.931609	-2.70884	7.09716	0	0	0	
+7.483	-0.931972	-2.70295	7.10305	0	0	0	
+7.484	-0.932334	-2.69704	7.10896	0	0	0	
+7.485	-0.932695	-2.69113	7.11487	0	0	0	
+7.486	-0.933055	-2.68521	7.12079	0	0	0	
+7.487	-0.933415	-2.67927	7.12673	0	0	0	
+7.488	-0.933773	-2.67333	7.13267	0	0	0	
+7.489	-0.93413	-2.66737	7.13863	0	0	0	
+7.49	-0.934487	-2.6614	7.1446	0	0	0	
+7.491	-0.934842	-2.65542	7.15058	0	0	0	
+7.492	-0.935197	-2.64944	7.15656	0	0	0	
+7.493	-0.935551	-2.64344	7.16256	0	0	0	
+7.494	-0.935903	-2.63743	7.16857	0	0	0	
+7.495	-0.936255	-2.63141	7.17459	0	0	0	
+7.496	-0.936606	-2.62538	7.18062	0	0	0	
+7.497	-0.936956	-2.61934	7.18666	0	0	0	
+7.498	-0.937305	-2.61329	7.19271	0	0	0	
+7.499	-0.937653	-2.60722	7.19878	0	0	0	
+7.5	-0.938	-2.60115	7.20485	0	0	0	
+7.501	-0.938346	-2.59507	7.21093	0	0	0	
+7.502	-0.938691	-2.58898	7.21702	0	0	0	
+7.503	-0.939036	-2.58287	7.22313	0	0	0	
+7.504	-0.939379	-2.57676	7.22924	0	0	0	
+7.505	-0.939721	-2.57063	7.23537	0	0	0	
+7.506	-0.940063	-2.5645	7.2415	0	0	0	
+7.507	-0.940403	-2.55836	7.24764	0	0	0	
+7.508	-0.940743	-2.5522	7.2538	0	0	0	
+7.509	-0.941082	-2.54604	7.25996	0	0	0	
+7.51	-0.941419	-2.53986	7.26614	0	0	0	
+7.511	-0.941756	-2.53367	7.27233	0	0	0	
+7.512	-0.942092	-2.52748	7.27852	0	0	0	
+7.513	-0.942427	-2.52127	7.28473	0	0	0	
+7.514	-0.942761	-2.51506	7.29094	0	0	0	
+7.515	-0.943094	-2.50883	7.29717	0	0	0	
+7.516	-0.943426	-2.5026	7.3034	0	0	0	
+7.517	-0.943757	-2.49635	7.30965	0	0	0	
+7.518	-0.944087	-2.49009	7.31591	0	0	0	
+7.519	-0.944416	-2.48383	7.32217	0	0	0	
+7.52	-0.944745	-2.47755	7.32845	0	0	0	
+7.521	-0.945072	-2.47127	7.33473	0	0	0	
+7.522	-0.945398	-2.46497	7.34103	0	0	0	
+7.523	-0.945724	-2.45867	7.34733	0	0	0	
+7.524	-0.946048	-2.45235	7.35365	0	0	0	
+7.525	-0.946372	-2.44603	7.35997	0	0	0	
+7.526	-0.946694	-2.43969	7.36631	0	0	0	
+7.527	-0.947016	-2.43335	7.37265	0	0	0	
+7.528	-0.947337	-2.42699	7.37901	0	0	0	
+7.529	-0.947657	-2.42063	7.38537	0	0	0	
+7.53	-0.947975	-2.41425	7.39175	0	0	0	
+7.531	-0.948293	-2.40787	7.39813	0	0	0	
+7.532	-0.94861	-2.40148	7.40452	0	0	0	
+7.533	-0.948926	-2.39508	7.41092	0	0	0	
+7.534	-0.949241	-2.38866	7.41734	0	0	0	
+7.535	-0.949555	-2.38224	7.42376	0	0	0	
+7.536	-0.949868	-2.37581	7.43019	0	0	0	
+7.537	-0.950181	-2.36937	7.43663	0	0	0	
+7.538	-0.950492	-2.36292	7.44308	0	0	0	
+7.539	-0.950802	-2.35646	7.44954	0	0	0	
+7.54	-0.951111	-2.34999	7.45601	0	0	0	
+7.541	-0.95142	-2.34351	7.46249	0	0	0	
+7.542	-0.951727	-2.33702	7.46898	0	0	0	
+7.543	-0.952034	-2.33053	7.47547	0	0	0	
+7.544	-0.952339	-2.32402	7.48198	0	0	0	
+7.545	-0.952644	-2.31751	7.48849	0	0	0	
+7.546	-0.952947	-2.31098	7.49502	0	0	0	
+7.547	-0.95325	-2.30445	7.50155	0	0	0	
+7.548	-0.953552	-2.2979	7.5081	0	0	0	
+7.549	-0.953852	-2.29135	7.51465	0	0	0	
+7.55	-0.954152	-2.28479	7.52121	0	0	0	
+7.551	-0.954451	-2.27822	7.52778	0	0	0	
+7.552	-0.954749	-2.27164	7.53436	0	0	0	
+7.553	-0.955046	-2.26505	7.54095	0	0	0	
+7.554	-0.955342	-2.25845	7.54755	0	0	0	
+7.555	-0.955637	-2.25184	7.55416	0	0	0	
+7.556	-0.955931	-2.24522	7.56078	0	0	0	
+7.557	-0.956224	-2.2386	7.5674	0	0	0	
+7.558	-0.956516	-2.23197	7.57403	0	0	0	
+7.559	-0.956807	-2.22532	7.58068	0	0	0	
+7.56	-0.957098	-2.21867	7.58733	0	0	0	
+7.561	-0.957387	-2.21201	7.59399	0	0	0	
+7.562	-0.957675	-2.20534	7.60066	0	0	0	
+7.563	-0.957963	-2.19866	7.60734	0	0	0	
+7.564	-0.958249	-2.19197	7.61403	0	0	0	
+7.565	-0.958535	-2.18528	7.62072	0	0	0	
+7.566	-0.958819	-2.17857	7.62743	0	0	0	
+7.567	-0.959103	-2.17186	7.63414	0	0	0	
+7.568	-0.959385	-2.16514	7.64086	0	0	0	
+7.569	-0.959667	-2.1584	7.6476	0	0	0	
+7.57	-0.959947	-2.15166	7.65434	0	0	0	
+7.571	-0.960227	-2.14492	7.66108	0	0	0	
+7.572	-0.960506	-2.13816	7.66784	0	0	0	
+7.573	-0.960784	-2.13139	7.67461	0	0	0	
+7.574	-0.961061	-2.12462	7.68138	0	0	0	
+7.575	-0.961336	-2.11784	7.68816	0	0	0	
+7.576	-0.961611	-2.11105	7.69495	0	0	0	
+7.577	-0.961885	-2.10425	7.70175	0	0	0	
+7.578	-0.962158	-2.09744	7.70856	0	0	0	
+7.579	-0.96243	-2.09062	7.71538	0	0	0	
+7.58	-0.962701	-2.0838	7.7222	0	0	0	
+7.581	-0.962971	-2.07697	7.72903	0	0	0	
+7.582	-0.96324	-2.07013	7.73587	0	0	0	
+7.583	-0.963509	-2.06328	7.74272	0	0	0	
+7.584	-0.963776	-2.05642	7.74958	0	0	0	
+7.585	-0.964042	-2.04955	7.75645	0	0	0	
+7.586	-0.964307	-2.04268	7.76332	0	0	0	
+7.587	-0.964572	-2.0358	7.7702	0	0	0	
+7.588	-0.964835	-2.02891	7.77709	0	0	0	
+7.589	-0.965097	-2.02201	7.78399	0	0	0	
+7.59	-0.965359	-2.0151	7.7909	0	0	0	
+7.591	-0.965619	-2.00819	7.79781	0	0	0	
+7.592	-0.965879	-2.00126	7.80474	0	0	0	
+7.593	-0.966137	-1.99433	7.81167	0	0	0	
+7.594	-0.966395	-1.98739	7.81861	0	0	0	
+7.595	-0.966651	-1.98045	7.82555	0	0	0	
+7.596	-0.966907	-1.97349	7.83251	0	0	0	
+7.597	-0.967162	-1.96653	7.83947	0	0	0	
+7.598	-0.967415	-1.95956	7.84644	0	0	0	
+7.599	-0.967668	-1.95258	7.85342	0	0	0	
+7.6	-0.96792	-1.94559	7.86041	0	0	0	
+7.601	-0.96817	-1.9386	7.8674	0	0	0	
+7.602	-0.96842	-1.9316	7.8744	0	0	0	
+7.603	-0.968669	-1.92459	7.88141	0	0	0	
+7.604	-0.968917	-1.91757	7.88843	0	0	0	
+7.605	-0.969164	-1.91055	7.89545	0	0	0	
+7.606	-0.96941	-1.90352	7.90248	0	0	0	
+7.607	-0.969655	-1.89648	7.90952	0	0	0	
+7.608	-0.969899	-1.88943	7.91657	0	0	0	
+7.609	-0.970142	-1.88237	7.92363	0	0	0	
+7.61	-0.970384	-1.87531	7.93069	0	0	0	
+7.611	-0.970625	-1.86824	7.93776	0	0	0	
+7.612	-0.970865	-1.86116	7.94484	0	0	0	
+7.613	-0.971104	-1.85408	7.95192	0	0	0	
+7.614	-0.971342	-1.84699	7.95901	0	0	0	
+7.615	-0.97158	-1.83989	7.96611	0	0	0	
+7.616	-0.971816	-1.83278	7.97322	0	0	0	
+7.617	-0.972051	-1.82566	7.98034	0	0	0	
+7.618	-0.972285	-1.81854	7.98746	0	0	0	
+7.619	-0.972519	-1.81141	7.99459	0	0	0	
+7.62	-0.972751	-1.80428	8.00172	0	0	0	
+7.621	-0.972982	-1.79713	8.00887	0	0	0	
+7.622	-0.973213	-1.78998	8.01602	0	0	0	
+7.623	-0.973442	-1.78283	8.02317	0	0	0	
+7.624	-0.973671	-1.77566	8.03034	0	0	0	
+7.625	-0.973898	-1.76849	8.03751	0	0	0	
+7.626	-0.974125	-1.76131	8.04469	0	0	0	
+7.627	-0.97435	-1.75412	8.05188	0	0	0	
+7.628	-0.974575	-1.74693	8.05907	0	0	0	
+7.629	-0.974798	-1.73973	8.06627	0	0	0	
+7.63	-0.975021	-1.73252	8.07348	0	0	0	
+7.631	-0.975242	-1.72531	8.08069	0	0	0	
+7.632	-0.975463	-1.71809	8.08791	0	0	0	
+7.633	-0.975683	-1.71086	8.09514	0	0	0	
+7.634	-0.975901	-1.70362	8.10238	0	0	0	
+7.635	-0.976119	-1.69638	8.10962	0	0	0	
+7.636	-0.976336	-1.68914	8.11686	0	0	0	
+7.637	-0.976552	-1.68188	8.12412	0	0	0	
+7.638	-0.976766	-1.67462	8.13138	0	0	0	
+7.639	-0.97698	-1.66735	8.13865	0	0	0	
+7.64	-0.977193	-1.66007	8.14593	0	0	0	
+7.641	-0.977405	-1.65279	8.15321	0	0	0	
+7.642	-0.977616	-1.6455	8.1605	0	0	0	
+7.643	-0.977826	-1.63821	8.16779	0	0	0	
+7.644	-0.978035	-1.63091	8.17509	0	0	0	
+7.645	-0.978243	-1.6236	8.1824	0	0	0	
+7.646	-0.97845	-1.61628	8.18972	0	0	0	
+7.647	-0.978656	-1.60896	8.19704	0	0	0	
+7.648	-0.978861	-1.60164	8.20436	0	0	0	
+7.649	-0.979065	-1.5943	8.2117	0	0	0	
+7.65	-0.979268	-1.58696	8.21904	0	0	0	
+7.651	-0.97947	-1.57962	8.22638	0	0	0	
+7.652	-0.979671	-1.57226	8.23374	0	0	0	
+7.653	-0.979871	-1.5649	8.2411	0	0	0	
+7.654	-0.98007	-1.55754	8.24846	0	0	0	
+7.655	-0.980268	-1.55017	8.25583	0	0	0	
+7.656	-0.980466	-1.54279	8.26321	0	0	0	
+7.657	-0.980662	-1.5354	8.2706	0	0	0	
+7.658	-0.980857	-1.52801	8.27799	0	0	0	
+7.659	-0.981051	-1.52062	8.28538	0	0	0	
+7.66	-0.981244	-1.51322	8.29278	0	0	0	
+7.661	-0.981437	-1.50581	8.30019	0	0	0	
+7.662	-0.981628	-1.49839	8.30761	0	0	0	
+7.663	-0.981818	-1.49097	8.31503	0	0	0	
+7.664	-0.982008	-1.48355	8.32245	0	0	0	
+7.665	-0.982196	-1.47611	8.32989	0	0	0	
+7.666	-0.982383	-1.46867	8.33733	0	0	0	
+7.667	-0.98257	-1.46123	8.34477	0	0	0	
+7.668	-0.982755	-1.45378	8.35222	0	0	0	
+7.669	-0.98294	-1.44632	8.35968	0	0	0	
+7.67	-0.983123	-1.43886	8.36714	0	0	0	
+7.671	-0.983306	-1.4314	8.3746	0	0	0	
+7.672	-0.983487	-1.42392	8.38208	0	0	0	
+7.673	-0.983667	-1.41644	8.38956	0	0	0	
+7.674	-0.983847	-1.40896	8.39704	0	0	0	
+7.675	-0.984026	-1.40147	8.40453	0	0	0	
+7.676	-0.984203	-1.39397	8.41203	0	0	0	
+7.677	-0.98438	-1.38647	8.41953	0	0	0	
+7.678	-0.984555	-1.37897	8.42703	0	0	0	
+7.679	-0.98473	-1.37145	8.43455	0	0	0	
+7.68	-0.984903	-1.36394	8.44206	0	0	0	
+7.681	-0.985076	-1.35641	8.44959	0	0	0	
+7.682	-0.985248	-1.34888	8.45712	0	0	0	
+7.683	-0.985418	-1.34135	8.46465	0	0	0	
+7.684	-0.985588	-1.33381	8.47219	0	0	0	
+7.685	-0.985757	-1.32627	8.47973	0	0	0	
+7.686	-0.985924	-1.31871	8.48729	0	0	0	
+7.687	-0.986091	-1.31116	8.49484	0	0	0	
+7.688	-0.986257	-1.3036	8.5024	0	0	0	
+7.689	-0.986421	-1.29603	8.50997	0	0	0	
+7.69	-0.986585	-1.28846	8.51754	0	0	0	
+7.691	-0.986748	-1.28089	8.52511	0	0	0	
+7.692	-0.98691	-1.2733	8.5327	0	0	0	
+7.693	-0.98707	-1.26572	8.54028	0	0	0	
+7.694	-0.98723	-1.25813	8.54787	0	0	0	
+7.695	-0.987389	-1.25053	8.55547	0	0	0	
+7.696	-0.987547	-1.24293	8.56307	0	0	0	
+7.697	-0.987704	-1.23532	8.57068	0	0	0	
+7.698	-0.98786	-1.22771	8.57829	0	0	0	
+7.699	-0.988014	-1.22009	8.58591	0	0	0	
+7.7	-0.988168	-1.21247	8.59353	0	0	0	
+7.701	-0.988321	-1.20485	8.60115	0	0	0	
+7.702	-0.988473	-1.19722	8.60878	0	0	0	
+7.703	-0.988624	-1.18958	8.61642	0	0	0	
+7.704	-0.988774	-1.18194	8.62406	0	0	0	
+7.705	-0.988923	-1.1743	8.6317	0	0	0	
+7.706	-0.989071	-1.16665	8.63935	0	0	0	
+7.707	-0.989218	-1.15899	8.64701	0	0	0	
+7.708	-0.989364	-1.15133	8.65467	0	0	0	
+7.709	-0.989509	-1.14367	8.66233	0	0	0	
+7.71	-0.989653	-1.136	8.67	0	0	0	
+7.711	-0.989796	-1.12833	8.67767	0	0	0	
+7.712	-0.989938	-1.12065	8.68535	0	0	0	
+7.713	-0.990079	-1.11297	8.69303	0	0	0	
+7.714	-0.990219	-1.10528	8.70072	0	0	0	
+7.715	-0.990358	-1.09759	8.70841	0	0	0	
+7.716	-0.990496	-1.0899	8.7161	0	0	0	
+7.717	-0.990633	-1.0822	8.7238	0	0	0	
+7.718	-0.990769	-1.07449	8.73151	0	0	0	
+7.719	-0.990904	-1.06678	8.73922	0	0	0	
+7.72	-0.991038	-1.05907	8.74693	0	0	0	
+7.721	-0.991171	-1.05136	8.75464	0	0	0	
+7.722	-0.991303	-1.04363	8.76237	0	0	0	
+7.723	-0.991434	-1.03591	8.77009	0	0	0	
+7.724	-0.991564	-1.02818	8.77782	0	0	0	
+7.725	-0.991693	-1.02045	8.78555	0	0	0	
+7.726	-0.991822	-1.01271	8.79329	0	0	0	
+7.727	-0.991949	-1.00497	8.80103	0	0	0	
+7.728	-0.992075	-0.997223	8.80878	0	0	0	
+7.729	-0.9922	-0.989473	8.81653	0	0	0	
+7.73	-0.992324	-0.98172	8.82428	0	0	0	
+7.731	-0.992447	-0.973963	8.83204	0	0	0	
+7.732	-0.992569	-0.966202	8.8398	0	0	0	
+7.733	-0.992691	-0.958437	8.84756	0	0	0	
+7.734	-0.992811	-0.950668	8.85533	0	0	0	
+7.735	-0.99293	-0.942895	8.8631	0	0	0	
+7.736	-0.993048	-0.935119	8.87088	0	0	0	
+7.737	-0.993165	-0.927338	8.87866	0	0	0	
+7.738	-0.993282	-0.919555	8.88645	0	0	0	
+7.739	-0.993397	-0.911767	8.89423	0	0	0	
+7.74	-0.993511	-0.903976	8.90202	0	0	0	
+7.741	-0.993624	-0.896181	8.90982	0	0	0	
+7.742	-0.993737	-0.888383	8.91762	0	0	0	
+7.743	-0.993848	-0.880581	8.92542	0	0	0	
+7.744	-0.993958	-0.872775	8.93322	0	0	0	
+7.745	-0.994067	-0.864966	8.94103	0	0	0	
+7.746	-0.994176	-0.857154	8.94885	0	0	0	
+7.747	-0.994283	-0.849338	8.95666	0	0	0	
+7.748	-0.994389	-0.841519	8.96448	0	0	0	
+7.749	-0.994494	-0.833696	8.9723	0	0	0	
+7.75	-0.994599	-0.82587	8.98013	0	0	0	
+7.751	-0.994702	-0.818041	8.98796	0	0	0	
+7.752	-0.994804	-0.810208	8.99579	0	0	0	
+7.753	-0.994906	-0.802372	9.00363	0	0	0	
+7.754	-0.995006	-0.794533	9.01147	0	0	0	
+7.755	-0.995105	-0.786691	9.01931	0	0	0	
+7.756	-0.995204	-0.778846	9.02715	0	0	0	
+7.757	-0.995301	-0.770997	9.035	0	0	0	
+7.758	-0.995397	-0.763146	9.04285	0	0	0	
+7.759	-0.995493	-0.755291	9.05071	0	0	0	
+7.76	-0.995587	-0.747434	9.05857	0	0	0	
+7.761	-0.99568	-0.739573	9.06643	0	0	0	
+7.762	-0.995773	-0.73171	9.07429	0	0	0	
+7.763	-0.995864	-0.723843	9.08216	0	0	0	
+7.764	-0.995954	-0.715974	9.09003	0	0	0	
+7.765	-0.996044	-0.708102	9.0979	0	0	0	
+7.766	-0.996132	-0.700226	9.10577	0	0	0	
+7.767	-0.996219	-0.692349	9.11365	0	0	0	
+7.768	-0.996306	-0.684468	9.12153	0	0	0	
+7.769	-0.996391	-0.676585	9.12942	0	0	0	
+7.77	-0.996476	-0.668699	9.1373	0	0	0	
+7.771	-0.996559	-0.66081	9.14519	0	0	0	
+7.772	-0.996641	-0.652918	9.15308	0	0	0	
+7.773	-0.996723	-0.645024	9.16098	0	0	0	
+7.774	-0.996803	-0.637128	9.16887	0	0	0	
+7.775	-0.996883	-0.629229	9.17677	0	0	0	
+7.776	-0.996961	-0.621327	9.18467	0	0	0	
+7.777	-0.997038	-0.613423	9.19258	0	0	0	
+7.778	-0.997115	-0.605516	9.20048	0	0	0	
+7.779	-0.99719	-0.597607	9.20839	0	0	0	
+7.78	-0.997265	-0.589696	9.2163	0	0	0	
+7.781	-0.997338	-0.581782	9.22422	0	0	0	
+7.782	-0.99741	-0.573866	9.23213	0	0	0	
+7.783	-0.997482	-0.565948	9.24005	0	0	0	
+7.784	-0.997552	-0.558027	9.24797	0	0	0	
+7.785	-0.997622	-0.550104	9.2559	0	0	0	
+7.786	-0.99769	-0.542179	9.26382	0	0	0	
+7.787	-0.997758	-0.534252	9.27175	0	0	0	
+7.788	-0.997824	-0.526322	9.27968	0	0	0	
+7.789	-0.997889	-0.518391	9.28761	0	0	0	
+7.79	-0.997954	-0.510457	9.29554	0	0	0	
+7.791	-0.998017	-0.502522	9.30348	0	0	0	
+7.792	-0.99808	-0.494584	9.31142	0	0	0	
+7.793	-0.998141	-0.486644	9.31936	0	0	0	
+7.794	-0.998202	-0.478703	9.3273	0	0	0	
+7.795	-0.998261	-0.47076	9.33524	0	0	0	
+7.796	-0.99832	-0.462814	9.34319	0	0	0	
+7.797	-0.998377	-0.454867	9.35113	0	0	0	
+7.798	-0.998433	-0.446918	9.35908	0	0	0	
+7.799	-0.998489	-0.438967	9.36703	0	0	0	
+7.8	-0.998543	-0.431015	9.37499	0	0	0	
+7.801	-0.998597	-0.42306	9.38294	0	0	0	
+7.802	-0.998649	-0.415104	9.3909	0	0	0	
+7.803	-0.998701	-0.407147	9.39885	0	0	0	
+7.804	-0.998751	-0.399187	9.40681	0	0	0	
+7.805	-0.998801	-0.391227	9.41477	0	0	0	
+7.806	-0.998849	-0.383264	9.42274	0	0	0	
+7.807	-0.998897	-0.3753	9.4307	0	0	0	
+7.808	-0.998943	-0.367335	9.43867	0	0	0	
+7.809	-0.998988	-0.359368	9.44663	0	0	0	
+7.81	-0.999033	-0.3514	9.4546	0	0	0	
+7.811	-0.999076	-0.34343	9.46257	0	0	0	
+7.812	-0.999119	-0.335459	9.47054	0	0	0	
+7.813	-0.99916	-0.327486	9.47851	0	0	0	
+7.814	-0.999201	-0.319512	9.48649	0	0	0	
+7.815	-0.99924	-0.311537	9.49446	0	0	0	
+7.816	-0.999279	-0.303561	9.50244	0	0	0	
+7.817	-0.999316	-0.295583	9.51042	0	0	0	
+7.818	-0.999353	-0.287605	9.5184	0	0	0	
+7.819	-0.999388	-0.279625	9.52638	0	0	0	
+7.82	-0.999423	-0.271644	9.53436	0	0	0	
+7.821	-0.999456	-0.263662	9.54234	0	0	0	
+7.822	-0.999489	-0.255679	9.55032	0	0	0	
+7.823	-0.99952	-0.247694	9.55831	0	0	0	
+7.824	-0.999551	-0.239709	9.56629	0	0	0	
+7.825	-0.99958	-0.231723	9.57428	0	0	0	
+7.826	-0.999609	-0.223736	9.58226	0	0	0	
+7.827	-0.999636	-0.215748	9.59025	0	0	0	
+7.828	-0.999662	-0.20776	9.59824	0	0	0	
+7.829	-0.999688	-0.19977	9.60623	0	0	0	
+7.83	-0.999712	-0.19178	9.61422	0	0	0	
+7.831	-0.999736	-0.183788	9.62221	0	0	0	
+7.832	-0.999758	-0.175796	9.6302	0	0	0	
+7.833	-0.99978	-0.167804	9.6382	0	0	0	
+7.834	-0.9998	-0.159811	9.64619	0	0	0	
+7.835	-0.99982	-0.151817	9.65418	0	0	0	
+7.836	-0.999838	-0.143822	9.66218	0	0	0	
+7.837	-0.999856	-0.135827	9.67017	0	0	0	
+7.838	-0.999872	-0.127831	9.67817	0	0	0	
+7.839	-0.999888	-0.119835	9.68616	0	0	0	
+7.84	-0.999902	-0.111838	9.69416	0	0	0	
+7.841	-0.999916	-0.103841	9.70216	0	0	0	
+7.842	-0.999928	-0.0958439	9.71016	0	0	0	
+7.843	-0.99994	-0.087846	9.71815	0	0	0	
+7.844	-0.99995	-0.0798478	9.72615	0	0	0	
+7.845	-0.99996	-0.0718492	9.73415	0	0	0	
+7.846	-0.999968	-0.0638504	9.74215	0	0	0	
+7.847	-0.999976	-0.0558513	9.75015	0	0	0	
+7.848	-0.999982	-0.0478519	9.75815	0	0	0	
+7.849	-0.999988	-0.0398524	9.76615	0	0	0	
+7.85	-0.999992	-0.0318527	9.77415	0	0	0	
+7.851	-0.999996	-0.0238529	9.78215	0	0	0	
+7.852	-0.999998	-0.015853	9.79015	0	0	0	
+7.853	-1	-0.00785307	9.79815	0	0	0	
+7.854	-1	0.000146928	9.80615	0	0	0	
+7.855	-0.999999	0.00814692	9.81415	0	0	0	
+7.856	-0.999998	0.0161469	9.82215	0	0	0	
+7.857	-0.999995	0.0241468	9.83015	0	0	0	
+7.858	-0.999992	0.0321466	9.83815	0	0	0	
+7.859	-0.999987	0.0401463	9.84615	0	0	0	
+7.86	-0.999982	0.0481458	9.85415	0	0	0	
+7.861	-0.999975	0.0561451	9.86215	0	0	0	
+7.862	-0.999968	0.0641442	9.87014	0	0	0	
+7.863	-0.999959	0.072143	9.87814	0	0	0	
+7.864	-0.99995	0.0801416	9.88614	0	0	0	
+7.865	-0.999939	0.0881398	9.89414	0	0	0	
+7.866	-0.999928	0.0961377	9.90214	0	0	0	
+7.867	-0.999915	0.104135	9.91014	0	0	0	
+7.868	-0.999902	0.112132	9.91813	0	0	0	
+7.869	-0.999887	0.120129	9.92613	0	0	0	
+7.87	-0.999872	0.128125	9.93413	0	0	0	
+7.871	-0.999855	0.136121	9.94212	0	0	0	
+7.872	-0.999838	0.144116	9.95012	0	0	0	
+7.873	-0.999819	0.15211	9.95811	0	0	0	
+7.874	-0.9998	0.160104	9.9661	0	0	0	
+7.875	-0.999779	0.168097	9.9741	0	0	0	
+7.876	-0.999758	0.17609	9.98209	0	0	0	
+7.877	-0.999735	0.184082	9.99008	0	0	0	
+7.878	-0.999712	0.192073	9.99807	0	0	0	
+7.879	-0.999687	0.200063	10.0061	0	0	0	
+7.88	-0.999662	0.208053	10.0141	0	0	0	
+7.881	-0.999635	0.216042	10.022	0	0	0	
+7.882	-0.999608	0.22403	10.03	0	0	0	
+7.883	-0.999579	0.232017	10.038	0	0	0	
+7.884	-0.999549	0.240003	10.046	0	0	0	
+7.885	-0.999519	0.247988	10.054	0	0	0	
+7.886	-0.999487	0.255972	10.062	0	0	0	
+7.887	-0.999455	0.263955	10.07	0	0	0	
+7.888	-0.999421	0.271937	10.0779	0	0	0	
+7.889	-0.999387	0.279918	10.0859	0	0	0	
+7.89	-0.999351	0.287898	10.0939	0	0	0	
+7.891	-0.999315	0.295876	10.1019	0	0	0	
+7.892	-0.999277	0.303854	10.1099	0	0	0	
+7.893	-0.999239	0.31183	10.1178	0	0	0	
+7.894	-0.999199	0.319805	10.1258	0	0	0	
+7.895	-0.999159	0.327779	10.1338	0	0	0	
+7.896	-0.999117	0.335751	10.1418	0	0	0	
+7.897	-0.999075	0.343723	10.1497	0	0	0	
+7.898	-0.999031	0.351692	10.1577	0	0	0	
+7.899	-0.998987	0.359661	10.1657	0	0	0	
+7.9	-0.998941	0.367627	10.1736	0	0	0	
+7.901	-0.998895	0.375593	10.1816	0	0	0	
+7.902	-0.998847	0.383557	10.1896	0	0	0	
+7.903	-0.998799	0.391519	10.1975	0	0	0	
+7.904	-0.998749	0.39948	10.2055	0	0	0	
+7.905	-0.998699	0.407439	10.2134	0	0	0	
+7.906	-0.998647	0.415397	10.2214	0	0	0	
+7.907	-0.998595	0.423353	10.2294	0	0	0	
+7.908	-0.998541	0.431307	10.2373	0	0	0	
+7.909	-0.998487	0.439259	10.2453	0	0	0	
+7.91	-0.998431	0.44721	10.2532	0	0	0	
+7.911	-0.998375	0.455159	10.2612	0	0	0	
+7.912	-0.998317	0.463106	10.2691	0	0	0	
+7.913	-0.998259	0.471051	10.2771	0	0	0	
+7.914	-0.998199	0.478995	10.285	0	0	0	
+7.915	-0.998139	0.486936	10.2929	0	0	0	
+7.916	-0.998077	0.494876	10.3009	0	0	0	
+7.917	-0.998015	0.502813	10.3088	0	0	0	
+7.918	-0.997952	0.510749	10.3167	0	0	0	
+7.919	-0.997887	0.518682	10.3247	0	0	0	
+7.92	-0.997822	0.526614	10.3326	0	0	0	
+7.921	-0.997755	0.534543	10.3405	0	0	0	
+7.922	-0.997688	0.54247	10.3485	0	0	0	
+7.923	-0.997619	0.550395	10.3564	0	0	0	
+7.924	-0.99755	0.558318	10.3643	0	0	0	
+7.925	-0.997479	0.566239	10.3722	0	0	0	
+7.926	-0.997408	0.574157	10.3802	0	0	0	
+7.927	-0.997335	0.582073	10.3881	0	0	0	
+7.928	-0.997262	0.589986	10.396	0	0	0	
+7.929	-0.997187	0.597898	10.4039	0	0	0	
+7.93	-0.997112	0.605807	10.4118	0	0	0	
+7.931	-0.997036	0.613713	10.4197	0	0	0	
+7.932	-0.996958	0.621617	10.4276	0	0	0	
+7.933	-0.99688	0.629519	10.4355	0	0	0	
+7.934	-0.9968	0.637418	10.4434	0	0	0	
+7.935	-0.99672	0.645314	10.4513	0	0	0	
+7.936	-0.996638	0.653208	10.4592	0	0	0	
+7.937	-0.996556	0.6611	10.4671	0	0	0	
+7.938	-0.996473	0.668988	10.475	0	0	0	
+7.939	-0.996388	0.676874	10.4829	0	0	0	
+7.94	-0.996303	0.684757	10.4908	0	0	0	
+7.941	-0.996216	0.692638	10.4986	0	0	0	
+7.942	-0.996129	0.700516	10.5065	0	0	0	
+7.943	-0.99604	0.708391	10.5144	0	0	0	
+7.944	-0.995951	0.716263	10.5223	0	0	0	
+7.945	-0.995861	0.724132	10.5301	0	0	0	
+7.946	-0.995769	0.731998	10.538	0	0	0	
+7.947	-0.995677	0.739862	10.5459	0	0	0	
+7.948	-0.995584	0.747722	10.5537	0	0	0	
+7.949	-0.995489	0.75558	10.5616	0	0	0	
+7.95	-0.995394	0.763434	10.5694	0	0	0	
+7.951	-0.995297	0.771286	10.5773	0	0	0	
+7.952	-0.9952	0.779134	10.5851	0	0	0	
+7.953	-0.995102	0.786979	10.593	0	0	0	
+7.954	-0.995002	0.794821	10.6008	0	0	0	
+7.955	-0.994902	0.80266	10.6087	0	0	0	
+7.956	-0.994801	0.810496	10.6165	0	0	0	
+7.957	-0.994698	0.818328	10.6243	0	0	0	
+7.958	-0.994595	0.826157	10.6322	0	0	0	
+7.959	-0.994491	0.833983	10.64	0	0	0	
+7.96	-0.994385	0.841806	10.6478	0	0	0	
+7.961	-0.994279	0.849625	10.6556	0	0	0	
+7.962	-0.994172	0.857441	10.6634	0	0	0	
+7.963	-0.994063	0.865253	10.6713	0	0	0	
+7.964	-0.993954	0.873062	10.6791	0	0	0	
+7.965	-0.993844	0.880867	10.6869	0	0	0	
+7.966	-0.993733	0.888669	10.6947	0	0	0	
+7.967	-0.99362	0.896467	10.7025	0	0	0	
+7.968	-0.993507	0.904262	10.7103	0	0	0	
+7.969	-0.993393	0.912053	10.7181	0	0	0	
+7.97	-0.993277	0.919841	10.7258	0	0	0	
+7.971	-0.993161	0.927624	10.7336	0	0	0	
+7.972	-0.993044	0.935404	10.7414	0	0	0	
+7.973	-0.992926	0.943181	10.7492	0	0	0	
+7.974	-0.992806	0.950953	10.757	0	0	0	
+7.975	-0.992686	0.958722	10.7647	0	0	0	
+7.976	-0.992565	0.966487	10.7725	0	0	0	
+7.977	-0.992443	0.974248	10.7802	0	0	0	
+7.978	-0.99232	0.982005	10.788	0	0	0	
+7.979	-0.992195	0.989758	10.7958	0	0	0	
+7.98	-0.99207	0.997507	10.8035	0	0	0	
+7.981	-0.991944	1.00525	10.8113	0	0	0	
+7.982	-0.991817	1.01299	10.819	0	0	0	
+7.983	-0.991689	1.02073	10.8267	0	0	0	
+7.984	-0.99156	1.02846	10.8345	0	0	0	
+7.985	-0.991429	1.03619	10.8422	0	0	0	
+7.986	-0.991298	1.04392	10.8499	0	0	0	
+7.987	-0.991166	1.05164	10.8576	0	0	0	
+7.988	-0.991033	1.05936	10.8654	0	0	0	
+7.989	-0.990899	1.06707	10.8731	0	0	0	
+7.99	-0.990764	1.07478	10.8808	0	0	0	
+7.991	-0.990628	1.08248	10.8885	0	0	0	
+7.992	-0.990491	1.09018	10.8962	0	0	0	
+7.993	-0.990352	1.09787	10.9039	0	0	0	
+7.994	-0.990213	1.10556	10.9116	0	0	0	
+7.995	-0.990073	1.11325	10.9192	0	0	0	
+7.996	-0.989932	1.12093	10.9269	0	0	0	
+7.997	-0.98979	1.12861	10.9346	0	0	0	
+7.998	-0.989647	1.13628	10.9423	0	0	0	
+7.999	-0.989503	1.14395	10.9499	0	0	0	
+8	-0.989358	1.15161	10.9576	0	0	0	
+8.001	-0.989212	1.15927	10.9653	0	0	0	
+8.002	-0.989065	1.16693	10.9729	0	0	0	
+8.003	-0.988917	1.17458	10.9806	0	0	0	
+8.004	-0.988768	1.18222	10.9882	0	0	0	
+8.005	-0.988618	1.18986	10.9959	0	0	0	
+8.006	-0.988467	1.1975	11.0035	0	0	0	
+8.007	-0.988316	1.20513	11.0111	0	0	0	
+8.008	-0.988163	1.21275	11.0188	0	0	0	
+8.009	-0.988009	1.22037	11.0264	0	0	0	
+8.01	-0.987854	1.22799	11.034	0	0	0	
+8.011	-0.987698	1.2356	11.0416	0	0	0	
+8.012	-0.987541	1.24321	11.0492	0	0	0	
+8.013	-0.987383	1.25081	11.0568	0	0	0	
+8.014	-0.987224	1.25841	11.0644	0	0	0	
+8.015	-0.987065	1.266	11.072	0	0	0	
+8.016	-0.986904	1.27358	11.0796	0	0	0	
+8.017	-0.986742	1.28116	11.0872	0	0	0	
+8.018	-0.986579	1.28874	11.0947	0	0	0	
+8.019	-0.986415	1.29631	11.1023	0	0	0	
+8.02	-0.986251	1.30388	11.1099	0	0	0	
+8.021	-0.986085	1.31144	11.1174	0	0	0	
+8.022	-0.985918	1.31899	11.125	0	0	0	
+8.023	-0.98575	1.32654	11.1325	0	0	0	
+8.024	-0.985582	1.33409	11.1401	0	0	0	
+8.025	-0.985412	1.34163	11.1476	0	0	0	
+8.026	-0.985241	1.34916	11.1552	0	0	0	
+8.027	-0.98507	1.35669	11.1627	0	0	0	
+8.028	-0.984897	1.36421	11.1702	0	0	0	
+8.029	-0.984723	1.37173	11.1777	0	0	0	
+8.03	-0.984549	1.37924	11.1852	0	0	0	
+8.031	-0.984373	1.38675	11.1927	0	0	0	
+8.032	-0.984197	1.39425	11.2002	0	0	0	
+8.033	-0.984019	1.40174	11.2077	0	0	0	
+8.034	-0.98384	1.40923	11.2152	0	0	0	
+8.035	-0.983661	1.41672	11.2227	0	0	0	
+8.036	-0.98348	1.4242	11.2302	0	0	0	
+8.037	-0.983299	1.43167	11.2377	0	0	0	
+8.038	-0.983116	1.43914	11.2451	0	0	0	
+8.039	-0.982933	1.4466	11.2526	0	0	0	
+8.04	-0.982748	1.45405	11.2601	0	0	0	
+8.041	-0.982563	1.4615	11.2675	0	0	0	
+8.042	-0.982377	1.46895	11.2749	0	0	0	
+8.043	-0.982189	1.47639	11.2824	0	0	0	
+8.044	-0.982001	1.48382	11.2898	0	0	0	
+8.045	-0.981811	1.49124	11.2972	0	0	0	
+8.046	-0.981621	1.49866	11.3047	0	0	0	
+8.047	-0.98143	1.50608	11.3121	0	0	0	
+8.048	-0.981237	1.51349	11.3195	0	0	0	
+8.049	-0.981044	1.52089	11.3269	0	0	0	
+8.05	-0.98085	1.52829	11.3343	0	0	0	
+8.051	-0.980655	1.53568	11.3417	0	0	0	
+8.052	-0.980458	1.54306	11.3491	0	0	0	
+8.053	-0.980261	1.55044	11.3564	0	0	0	
+8.054	-0.980063	1.55781	11.3638	0	0	0	
+8.055	-0.979864	1.56517	11.3712	0	0	0	
+8.056	-0.979664	1.57253	11.3785	0	0	0	
+8.057	-0.979462	1.57989	11.3859	0	0	0	
+8.058	-0.97926	1.58723	11.3932	0	0	0	
+8.059	-0.979057	1.59457	11.4006	0	0	0	
+8.06	-0.978853	1.60191	11.4079	0	0	0	
+8.061	-0.978648	1.60923	11.4152	0	0	0	
+8.062	-0.978442	1.61655	11.4226	0	0	0	
+8.063	-0.978235	1.62387	11.4299	0	0	0	
+8.064	-0.978027	1.63118	11.4372	0	0	0	
+8.065	-0.977818	1.63848	11.4445	0	0	0	
+8.066	-0.977608	1.64577	11.4518	0	0	0	
+8.067	-0.977397	1.65306	11.4591	0	0	0	
+8.068	-0.977185	1.66034	11.4663	0	0	0	
+8.069	-0.976972	1.66762	11.4736	0	0	0	
+8.07	-0.976759	1.67489	11.4809	0	0	0	
+8.071	-0.976544	1.68215	11.4881	0	0	0	
+8.072	-0.976328	1.6894	11.4954	0	0	0	
+8.073	-0.976111	1.69665	11.5026	0	0	0	
+8.074	-0.975893	1.70389	11.5099	0	0	0	
+8.075	-0.975675	1.71113	11.5171	0	0	0	
+8.076	-0.975455	1.71835	11.5244	0	0	0	
+8.077	-0.975234	1.72557	11.5316	0	0	0	
+8.078	-0.975013	1.73279	11.5388	0	0	0	
+8.079	-0.97479	1.73999	11.546	0	0	0	
+8.08	-0.974566	1.74719	11.5532	0	0	0	
+8.081	-0.974342	1.75439	11.5604	0	0	0	
+8.082	-0.974116	1.76157	11.5676	0	0	0	
+8.083	-0.97389	1.76875	11.5748	0	0	0	
+8.084	-0.973662	1.77592	11.5819	0	0	0	
+8.085	-0.973434	1.78309	11.5891	0	0	0	
+8.086	-0.973204	1.79025	11.5962	0	0	0	
+8.087	-0.972974	1.7974	11.6034	0	0	0	
+8.088	-0.972742	1.80454	11.6105	0	0	0	
+8.089	-0.97251	1.81168	11.6177	0	0	0	
+8.09	-0.972277	1.8188	11.6248	0	0	0	
+8.091	-0.972042	1.82593	11.6319	0	0	0	
+8.092	-0.971807	1.83304	11.639	0	0	0	
+8.093	-0.971571	1.84015	11.6461	0	0	0	
+8.094	-0.971334	1.84725	11.6532	0	0	0	
+8.095	-0.971095	1.85434	11.6603	0	0	0	
+8.096	-0.970856	1.86142	11.6674	0	0	0	
+8.097	-0.970616	1.8685	11.6745	0	0	0	
+8.098	-0.970375	1.87557	11.6816	0	0	0	
+8.099	-0.970133	1.88263	11.6886	0	0	0	
+8.1	-0.96989	1.88969	11.6957	0	0	0	
+8.101	-0.969646	1.89674	11.7027	0	0	0	
+8.102	-0.969401	1.90377	11.7098	0	0	0	
+8.103	-0.969155	1.91081	11.7168	0	0	0	
+8.104	-0.968908	1.91783	11.7238	0	0	0	
+8.105	-0.96866	1.92485	11.7308	0	0	0	
+8.106	-0.968411	1.93186	11.7379	0	0	0	
+8.107	-0.968161	1.93886	11.7449	0	0	0	
+8.108	-0.96791	1.94585	11.7519	0	0	0	
+8.109	-0.967659	1.95284	11.7588	0	0	0	
+8.11	-0.967406	1.95982	11.7658	0	0	0	
+8.111	-0.967152	1.96679	11.7728	0	0	0	
+8.112	-0.966898	1.97375	11.7797	0	0	0	
+8.113	-0.966642	1.9807	11.7867	0	0	0	
+8.114	-0.966385	1.98765	11.7936	0	0	0	
+8.115	-0.966128	1.99459	11.8006	0	0	0	
+8.116	-0.965869	2.00152	11.8075	0	0	0	
+8.117	-0.96561	2.00844	11.8144	0	0	0	
+8.118	-0.965349	2.01535	11.8214	0	0	0	
+8.119	-0.965088	2.02226	11.8283	0	0	0	
+8.12	-0.964825	2.02916	11.8352	0	0	0	
+8.121	-0.964562	2.03605	11.842	0	0	0	
+8.122	-0.964298	2.04293	11.8489	0	0	0	
+8.123	-0.964032	2.0498	11.8558	0	0	0	
+8.124	-0.963766	2.05667	11.8627	0	0	0	
+8.125	-0.963499	2.06353	11.8695	0	0	0	
+8.126	-0.963231	2.07038	11.8764	0	0	0	
+8.127	-0.962961	2.07722	11.8832	0	0	0	
+8.128	-0.962691	2.08405	11.89	0	0	0	
+8.129	-0.96242	2.09087	11.8969	0	0	0	
+8.13	-0.962148	2.09769	11.9037	0	0	0	
+8.131	-0.961875	2.1045	11.9105	0	0	0	
+8.132	-0.961601	2.1113	11.9173	0	0	0	
+8.133	-0.961326	2.11809	11.9241	0	0	0	
+8.134	-0.96105	2.12487	11.9309	0	0	0	
+8.135	-0.960774	2.13164	11.9376	0	0	0	
+8.136	-0.960496	2.13841	11.9444	0	0	0	
+8.137	-0.960217	2.14516	11.9512	0	0	0	
+8.138	-0.959937	2.15191	11.9579	0	0	0	
+8.139	-0.959656	2.15865	11.9647	0	0	0	
+8.14	-0.959375	2.16538	11.9714	0	0	0	
+8.141	-0.959092	2.1721	11.9781	0	0	0	
+8.142	-0.958809	2.17882	11.9848	0	0	0	
+8.143	-0.958524	2.18552	11.9915	0	0	0	
+8.144	-0.958239	2.19222	11.9982	0	0	0	
+8.145	-0.957952	2.19891	12.0049	0	0	0	
+8.146	-0.957665	2.20558	12.0116	0	0	0	
+8.147	-0.957376	2.21225	12.0183	0	0	0	
+8.148	-0.957087	2.21891	12.0249	0	0	0	
+8.149	-0.956797	2.22557	12.0316	0	0	0	
+8.15	-0.956506	2.23221	12.0382	0	0	0	
+8.151	-0.956213	2.23884	12.0448	0	0	0	
+8.152	-0.95592	2.24547	12.0515	0	0	0	
+8.153	-0.955626	2.25208	12.0581	0	0	0	
+8.154	-0.955331	2.25869	12.0647	0	0	0	
+8.155	-0.955035	2.26529	12.0713	0	0	0	
+8.156	-0.954738	2.27188	12.0779	0	0	0	
+8.157	-0.95444	2.27846	12.0845	0	0	0	
+8.158	-0.954141	2.28503	12.091	0	0	0	
+8.159	-0.953841	2.29159	12.0976	0	0	0	
+8.16	-0.953541	2.29814	12.1041	0	0	0	
+8.161	-0.953239	2.30469	12.1107	0	0	0	
+8.162	-0.952936	2.31122	12.1172	0	0	0	
+8.163	-0.952633	2.31774	12.1237	0	0	0	
+8.164	-0.952328	2.32426	12.1303	0	0	0	
+8.165	-0.952022	2.33077	12.1368	0	0	0	
+8.166	-0.951716	2.33726	12.1433	0	0	0	
+8.167	-0.951408	2.34375	12.1498	0	0	0	
+8.168	-0.9511	2.35023	12.1562	0	0	0	
+8.169	-0.950791	2.3567	12.1627	0	0	0	
+8.17	-0.95048	2.36316	12.1692	0	0	0	
+8.171	-0.950169	2.36961	12.1756	0	0	0	
+8.172	-0.949857	2.37605	12.182	0	0	0	
+8.173	-0.949544	2.38248	12.1885	0	0	0	
+8.174	-0.94923	2.3889	12.1949	0	0	0	
+8.175	-0.948915	2.39531	12.2013	0	0	0	
+8.176	-0.948599	2.40171	12.2077	0	0	0	
+8.177	-0.948282	2.40811	12.2141	0	0	0	
+8.178	-0.947964	2.41449	12.2205	0	0	0	
+8.179	-0.947645	2.42086	12.2269	0	0	0	
+8.18	-0.947325	2.42723	12.2332	0	0	0	
+8.181	-0.947004	2.43358	12.2396	0	0	0	
+8.182	-0.946683	2.43992	12.2459	0	0	0	
+8.183	-0.94636	2.44626	12.2523	0	0	0	
+8.184	-0.946036	2.45258	12.2586	0	0	0	
+8.185	-0.945712	2.4589	12.2649	0	0	0	
+8.186	-0.945386	2.4652	12.2712	0	0	0	
+8.187	-0.94506	2.4715	12.2775	0	0	0	
+8.188	-0.944733	2.47778	12.2838	0	0	0	
+8.189	-0.944404	2.48406	12.2901	0	0	0	
+8.19	-0.944075	2.49032	12.2963	0	0	0	
+8.191	-0.943745	2.49658	12.3026	0	0	0	
+8.192	-0.943414	2.50283	12.3088	0	0	0	
+8.193	-0.943082	2.50906	12.3151	0	0	0	
+8.194	-0.942749	2.51529	12.3213	0	0	0	
+8.195	-0.942415	2.5215	12.3275	0	0	0	
+8.196	-0.94208	2.52771	12.3337	0	0	0	
+8.197	-0.941744	2.5339	12.3399	0	0	0	
+8.198	-0.941407	2.54009	12.3461	0	0	0	
+8.199	-0.941069	2.54626	12.3523	0	0	0	
+8.2	-0.940731	2.55243	12.3584	0	0	0	
+8.201	-0.940391	2.55858	12.3646	0	0	0	
+8.202	-0.94005	2.56473	12.3707	0	0	0	
+8.203	-0.939709	2.57086	12.3769	0	0	0	
+8.204	-0.939366	2.57698	12.383	0	0	0	
+8.205	-0.939023	2.5831	12.3891	0	0	0	
+8.206	-0.938679	2.5892	12.3952	0	0	0	
+8.207	-0.938333	2.59529	12.4013	0	0	0	
+8.208	-0.937987	2.60137	12.4074	0	0	0	
+8.209	-0.93764	2.60745	12.4134	0	0	0	
+8.21	-0.937292	2.61351	12.4195	0	0	0	
+8.211	-0.936943	2.61956	12.4256	0	0	0	
+8.212	-0.936593	2.6256	12.4316	0	0	0	
+8.213	-0.936242	2.63163	12.4376	0	0	0	
+8.214	-0.93589	2.63765	12.4436	0	0	0	
+8.215	-0.935538	2.64366	12.4497	0	0	0	
+8.216	-0.935184	2.64966	12.4557	0	0	0	
+8.217	-0.934829	2.65564	12.4616	0	0	0	
+8.218	-0.934474	2.66162	12.4676	0	0	0	
+8.219	-0.934117	2.66759	12.4736	0	0	0	
+8.22	-0.93376	2.67354	12.4795	0	0	0	
+8.221	-0.933401	2.67949	12.4855	0	0	0	
+8.222	-0.933042	2.68542	12.4914	0	0	0	
+8.223	-0.932682	2.69135	12.4973	0	0	0	
+8.224	-0.932321	2.69726	12.5033	0	0	0	
+8.225	-0.931959	2.70316	12.5092	0	0	0	
+8.226	-0.931596	2.70905	12.5151	0	0	0	
+8.227	-0.931232	2.71493	12.5209	0	0	0	
+8.228	-0.930867	2.7208	12.5268	0	0	0	
+8.229	-0.930501	2.72666	12.5327	0	0	0	
+8.23	-0.930134	2.73251	12.5385	0	0	0	
+8.231	-0.929766	2.73835	12.5443	0	0	0	
+8.232	-0.929398	2.74417	12.5502	0	0	0	
+8.233	-0.929028	2.74999	12.556	0	0	0	
+8.234	-0.928658	2.75579	12.5618	0	0	0	
+8.235	-0.928286	2.76159	12.5676	0	0	0	
+8.236	-0.927914	2.76737	12.5734	0	0	0	
+8.237	-0.927541	2.77314	12.5791	0	0	0	
+8.238	-0.927167	2.7789	12.5849	0	0	0	
+8.239	-0.926792	2.78465	12.5906	0	0	0	
+8.24	-0.926415	2.79038	12.5964	0	0	0	
+8.241	-0.926039	2.79611	12.6021	0	0	0	
+8.242	-0.925661	2.80183	12.6078	0	0	0	
+8.243	-0.925282	2.80753	12.6135	0	0	0	
+8.244	-0.924902	2.81322	12.6192	0	0	0	
+8.245	-0.924521	2.8189	12.6249	0	0	0	
+8.246	-0.92414	2.82457	12.6306	0	0	0	
+8.247	-0.923757	2.83023	12.6362	0	0	0	
+8.248	-0.923374	2.83588	12.6419	0	0	0	
+8.249	-0.922989	2.84152	12.6475	0	0	0	
+8.25	-0.922604	2.84714	12.6531	0	0	0	
+8.251	-0.922218	2.85275	12.6588	0	0	0	
+8.252	-0.921831	2.85836	12.6644	0	0	0	
+8.253	-0.921443	2.86395	12.6699	0	0	0	
+8.254	-0.921054	2.86953	12.6755	0	0	0	
+8.255	-0.920664	2.87509	12.6811	0	0	0	
+8.256	-0.920273	2.88065	12.6867	0	0	0	
+8.257	-0.919881	2.8862	12.6922	0	0	0	
+8.258	-0.919489	2.89173	12.6977	0	0	0	
+8.259	-0.919095	2.89725	12.7033	0	0	0	
+8.26	-0.918701	2.90276	12.7088	0	0	0	
+8.261	-0.918305	2.90826	12.7143	0	0	0	
+8.262	-0.917909	2.91375	12.7197	0	0	0	
+8.263	-0.917512	2.91922	12.7252	0	0	0	
+8.264	-0.917114	2.92468	12.7307	0	0	0	
+8.265	-0.916714	2.93014	12.7361	0	0	0	
+8.266	-0.916314	2.93558	12.7416	0	0	0	
+8.267	-0.915913	2.941	12.747	0	0	0	
+8.268	-0.915512	2.94642	12.7524	0	0	0	
+8.269	-0.915109	2.95182	12.7578	0	0	0	
+8.27	-0.914705	2.95722	12.7632	0	0	0	
+8.271	-0.914301	2.9626	12.7686	0	0	0	
+8.272	-0.913895	2.96797	12.774	0	0	0	
+8.273	-0.913489	2.97333	12.7793	0	0	0	
+8.274	-0.913081	2.97867	12.7847	0	0	0	
+8.275	-0.912673	2.984	12.79	0	0	0	
+8.276	-0.912264	2.98933	12.7953	0	0	0	
+8.277	-0.911854	2.99464	12.8006	0	0	0	
+8.278	-0.911443	2.99993	12.8059	0	0	0	
+8.279	-0.911031	3.00522	12.8112	0	0	0	
+8.28	-0.910618	3.01049	12.8165	0	0	0	
+8.281	-0.910205	3.01575	12.8218	0	0	0	
+8.282	-0.90979	3.021	12.827	0	0	0	
+8.283	-0.909375	3.02624	12.8322	0	0	0	
+8.284	-0.908958	3.03147	12.8375	0	0	0	
+8.285	-0.908541	3.03668	12.8427	0	0	0	
+8.286	-0.908123	3.04188	12.8479	0	0	0	
+8.287	-0.907703	3.04707	12.8531	0	0	0	
+8.288	-0.907283	3.05225	12.8582	0	0	0	
+8.289	-0.906862	3.05741	12.8634	0	0	0	
+8.29	-0.90644	3.06256	12.8686	0	0	0	
+8.291	-0.906018	3.0677	12.8737	0	0	0	
+8.292	-0.905594	3.07283	12.8788	0	0	0	
+8.293	-0.905169	3.07795	12.8839	0	0	0	
+8.294	-0.904744	3.08305	12.889	0	0	0	
+8.295	-0.904317	3.08814	12.8941	0	0	0	
+8.296	-0.90389	3.09322	12.8992	0	0	0	
+8.297	-0.903462	3.09828	12.9043	0	0	0	
+8.298	-0.903033	3.10334	12.9093	0	0	0	
+8.299	-0.902603	3.10838	12.9144	0	0	0	
+8.3	-0.902172	3.11341	12.9194	0	0	0	
+8.301	-0.90174	3.11842	12.9244	0	0	0	
+8.302	-0.901307	3.12343	12.9294	0	0	0	
+8.303	-0.900874	3.12842	12.9344	0	0	0	
+8.304	-0.900439	3.1334	12.9394	0	0	0	
+8.305	-0.900004	3.13837	12.9444	0	0	0	
+8.306	-0.899567	3.14332	12.9493	0	0	0	
+8.307	-0.89913	3.14826	12.9543	0	0	0	
+8.308	-0.898692	3.15319	12.9592	0	0	0	
+8.309	-0.898253	3.15811	12.9641	0	0	0	
+8.31	-0.897813	3.16301	12.969	0	0	0	
+8.311	-0.897372	3.1679	12.9739	0	0	0	
+8.312	-0.89693	3.17278	12.9788	0	0	0	
+8.313	-0.896488	3.17764	12.9836	0	0	0	
+8.314	-0.896044	3.1825	12.9885	0	0	0	
+8.315	-0.8956	3.18734	12.9933	0	0	0	
+8.316	-0.895155	3.19216	12.9982	0	0	0	
+8.317	-0.894708	3.19698	13.003	0	0	0	
+8.318	-0.894261	3.20178	13.0078	0	0	0	
+8.319	-0.893813	3.20657	13.0126	0	0	0	
+8.32	-0.893364	3.21134	13.0173	0	0	0	
+8.321	-0.892915	3.21611	13.0221	0	0	0	
+8.322	-0.892464	3.22086	13.0269	0	0	0	
+8.323	-0.892012	3.22559	13.0316	0	0	0	
+8.324	-0.89156	3.23032	13.0363	0	0	0	
+8.325	-0.891107	3.23503	13.041	0	0	0	
+8.326	-0.890652	3.23973	13.0457	0	0	0	
+8.327	-0.890197	3.24442	13.0504	0	0	0	
+8.328	-0.889741	3.24909	13.0551	0	0	0	
+8.329	-0.889284	3.25375	13.0597	0	0	0	
+8.33	-0.888827	3.25839	13.0644	0	0	0	
+8.331	-0.888368	3.26303	13.069	0	0	0	
+8.332	-0.887908	3.26765	13.0736	0	0	0	
+8.333	-0.887448	3.27226	13.0783	0	0	0	
+8.334	-0.886986	3.27685	13.0829	0	0	0	
+8.335	-0.886524	3.28143	13.0874	0	0	0	
+8.336	-0.886061	3.286	13.092	0	0	0	
+8.337	-0.885597	3.29056	13.0966	0	0	0	
+8.338	-0.885132	3.2951	13.1011	0	0	0	
+8.339	-0.884666	3.29963	13.1056	0	0	0	
+8.34	-0.8842	3.30414	13.1101	0	0	0	
+8.341	-0.883732	3.30864	13.1146	0	0	0	
+8.342	-0.883264	3.31313	13.1191	0	0	0	
+8.343	-0.882794	3.31761	13.1236	0	0	0	
+8.344	-0.882324	3.32207	13.1281	0	0	0	
+8.345	-0.881853	3.32652	13.1325	0	0	0	
+8.346	-0.881381	3.33096	13.137	0	0	0	
+8.347	-0.880908	3.33538	13.1414	0	0	0	
+8.348	-0.880435	3.33979	13.1458	0	0	0	
+8.349	-0.87996	3.34418	13.1502	0	0	0	
+8.35	-0.879484	3.34857	13.1546	0	0	0	
+8.351	-0.879008	3.35294	13.1589	0	0	0	
+8.352	-0.878531	3.35729	13.1633	0	0	0	
+8.353	-0.878053	3.36163	13.1676	0	0	0	
+8.354	-0.877574	3.36596	13.172	0	0	0	
+8.355	-0.877094	3.37028	13.1763	0	0	0	
+8.356	-0.876613	3.37458	13.1806	0	0	0	
+8.357	-0.876131	3.37887	13.1849	0	0	0	
+8.358	-0.875649	3.38314	13.1891	0	0	0	
+8.359	-0.875166	3.38741	13.1934	0	0	0	
+8.36	-0.874681	3.39165	13.1977	0	0	0	
+8.361	-0.874196	3.39589	13.2019	0	0	0	
+8.362	-0.87371	3.40011	13.2061	0	0	0	
+8.363	-0.873223	3.40432	13.2103	0	0	0	
+8.364	-0.872736	3.40851	13.2145	0	0	0	
+8.365	-0.872247	3.41269	13.2187	0	0	0	
+8.366	-0.871757	3.41686	13.2229	0	0	0	
+8.367	-0.871267	3.42101	13.227	0	0	0	
+8.368	-0.870776	3.42515	13.2311	0	0	0	
+8.369	-0.870284	3.42927	13.2353	0	0	0	
+8.37	-0.869791	3.43338	13.2394	0	0	0	
+8.371	-0.869297	3.43748	13.2435	0	0	0	
+8.372	-0.868802	3.44156	13.2476	0	0	0	
+8.373	-0.868307	3.44563	13.2516	0	0	0	
+8.374	-0.86781	3.44969	13.2557	0	0	0	
+8.375	-0.867313	3.45373	13.2597	0	0	0	
+8.376	-0.866815	3.45776	13.2638	0	0	0	
+8.377	-0.866315	3.46178	13.2678	0	0	0	
+8.378	-0.865816	3.46578	13.2718	0	0	0	
+8.379	-0.865315	3.46977	13.2758	0	0	0	
+8.38	-0.864813	3.47374	13.2797	0	0	0	
+8.381	-0.864311	3.4777	13.2837	0	0	0	
+8.382	-0.863807	3.48164	13.2876	0	0	0	
+8.383	-0.863303	3.48558	13.2916	0	0	0	
+8.384	-0.862798	3.48949	13.2955	0	0	0	
+8.385	-0.862292	3.4934	13.2994	0	0	0	
+8.386	-0.861785	3.49729	13.3033	0	0	0	
+8.387	-0.861277	3.50116	13.3072	0	0	0	
+8.388	-0.860769	3.50502	13.311	0	0	0	
+8.389	-0.860259	3.50887	13.3149	0	0	0	
+8.39	-0.859749	3.51271	13.3187	0	0	0	
+8.391	-0.859238	3.51653	13.3225	0	0	0	
+8.392	-0.858726	3.52033	13.3263	0	0	0	
+8.393	-0.858213	3.52412	13.3301	0	0	0	
+8.394	-0.857699	3.5279	13.3339	0	0	0	
+8.395	-0.857185	3.53166	13.3377	0	0	0	
+8.396	-0.856669	3.53541	13.3414	0	0	0	
+8.397	-0.856153	3.53915	13.3451	0	0	0	
+8.398	-0.855636	3.54287	13.3489	0	0	0	
+8.399	-0.855118	3.54658	13.3526	0	0	0	
+8.4	-0.854599	3.55027	13.3563	0	0	0	
+8.401	-0.854079	3.55395	13.3599	0	0	0	
+8.402	-0.853559	3.55761	13.3636	0	0	0	
+8.403	-0.853037	3.56126	13.3673	0	0	0	
+8.404	-0.852515	3.5649	13.3709	0	0	0	
+8.405	-0.851992	3.56852	13.3745	0	0	0	
+8.406	-0.851468	3.57212	13.3781	0	0	0	
+8.407	-0.850943	3.57572	13.3817	0	0	0	
+8.408	-0.850417	3.5793	13.3853	0	0	0	
+8.409	-0.849891	3.58286	13.3889	0	0	0	
+8.41	-0.849363	3.58641	13.3924	0	0	0	
+8.411	-0.848835	3.58995	13.3959	0	0	0	
+8.412	-0.848306	3.59347	13.3995	0	0	0	
+8.413	-0.847776	3.59697	13.403	0	0	0	
+8.414	-0.847245	3.60047	13.4065	0	0	0	
+8.415	-0.846714	3.60394	13.4099	0	0	0	
+8.416	-0.846181	3.60741	13.4134	0	0	0	
+8.417	-0.845648	3.61086	13.4169	0	0	0	
+8.418	-0.845114	3.61429	13.4203	0	0	0	
+8.419	-0.844579	3.61771	13.4237	0	0	0	
+8.42	-0.844043	3.62112	13.4271	0	0	0	
+8.421	-0.843506	3.62451	13.4305	0	0	0	
+8.422	-0.842969	3.62789	13.4339	0	0	0	
+8.423	-0.84243	3.63125	13.4372	0	0	0	
+8.424	-0.841891	3.6346	13.4406	0	0	0	
+8.425	-0.841351	3.63793	13.4439	0	0	0	
+8.426	-0.84081	3.64125	13.4472	0	0	0	
+8.427	-0.840268	3.64455	13.4506	0	0	0	
+8.428	-0.839726	3.64784	13.4538	0	0	0	
+8.429	-0.839182	3.65112	13.4571	0	0	0	
+8.43	-0.838638	3.65438	13.4604	0	0	0	
+8.431	-0.838093	3.65762	13.4636	0	0	0	
+8.432	-0.837547	3.66085	13.4669	0	0	0	
+8.433	-0.837	3.66407	13.4701	0	0	0	
+8.434	-0.836453	3.66727	13.4733	0	0	0	
+8.435	-0.835904	3.67046	13.4765	0	0	0	
+8.436	-0.835355	3.67363	13.4796	0	0	0	
+8.437	-0.834805	3.67679	13.4828	0	0	0	
+8.438	-0.834254	3.67993	13.4859	0	0	0	
+8.439	-0.833702	3.68306	13.4891	0	0	0	
+8.44	-0.833149	3.68617	13.4922	0	0	0	
+8.441	-0.832596	3.68927	13.4953	0	0	0	
+8.442	-0.832042	3.69236	13.4984	0	0	0	
+8.443	-0.831486	3.69543	13.5014	0	0	0	
+8.444	-0.83093	3.69848	13.5045	0	0	0	
+8.445	-0.830374	3.70152	13.5075	0	0	0	
+8.446	-0.829816	3.70454	13.5105	0	0	0	
+8.447	-0.829258	3.70755	13.5136	0	0	0	
+8.448	-0.828698	3.71055	13.5166	0	0	0	
+8.449	-0.828138	3.71353	13.5195	0	0	0	
+8.45	-0.827577	3.7165	13.5225	0	0	0	
+8.451	-0.827016	3.71945	13.5254	0	0	0	
+8.452	-0.826453	3.72238	13.5284	0	0	0	
+8.453	-0.825889	3.7253	13.5313	0	0	0	
+8.454	-0.825325	3.72821	13.5342	0	0	0	
+8.455	-0.82476	3.7311	13.5371	0	0	0	
+8.456	-0.824194	3.73398	13.54	0	0	0	
+8.457	-0.823628	3.73684	13.5428	0	0	0	
+8.458	-0.82306	3.73968	13.5457	0	0	0	
+8.459	-0.822492	3.74252	13.5485	0	0	0	
+8.46	-0.821922	3.74533	13.5513	0	0	0	
+8.461	-0.821352	3.74813	13.5541	0	0	0	
+8.462	-0.820782	3.75092	13.5569	0	0	0	
+8.463	-0.82021	3.75369	13.5597	0	0	0	
+8.464	-0.819637	3.75645	13.5624	0	0	0	
+8.465	-0.819064	3.75919	13.5652	0	0	0	
+8.466	-0.81849	3.76192	13.5679	0	0	0	
+8.467	-0.817915	3.76463	13.5706	0	0	0	
+8.468	-0.817339	3.76732	13.5733	0	0	0	
+8.469	-0.816763	3.77	13.576	0	0	0	
+8.47	-0.816185	3.77267	13.5787	0	0	0	
+8.471	-0.815607	3.77532	13.5813	0	0	0	
+8.472	-0.815028	3.77796	13.584	0	0	0	
+8.473	-0.814448	3.78058	13.5866	0	0	0	
+8.474	-0.813868	3.78318	13.5892	0	0	0	
+8.475	-0.813286	3.78577	13.5918	0	0	0	
+8.476	-0.812704	3.78835	13.5943	0	0	0	
+8.477	-0.812121	3.79091	13.5969	0	0	0	
+8.478	-0.811537	3.79345	13.5995	0	0	0	
+8.479	-0.810952	3.79598	13.602	0	0	0	
+8.48	-0.810367	3.7985	13.6045	0	0	0	
+8.481	-0.809781	3.801	13.607	0	0	0	
+8.482	-0.809193	3.80348	13.6095	0	0	0	
+8.483	-0.808605	3.80595	13.612	0	0	0	
+8.484	-0.808017	3.80841	13.6144	0	0	0	
+8.485	-0.807427	3.81084	13.6168	0	0	0	
+8.486	-0.806837	3.81327	13.6193	0	0	0	
+8.487	-0.806246	3.81568	13.6217	0	0	0	
+8.488	-0.805654	3.81807	13.6241	0	0	0	
+8.489	-0.805061	3.82045	13.6264	0	0	0	
+8.49	-0.804467	3.82281	13.6288	0	0	0	
+8.491	-0.803873	3.82516	13.6312	0	0	0	
+8.492	-0.803278	3.82749	13.6335	0	0	0	
+8.493	-0.802682	3.8298	13.6358	0	0	0	
+8.494	-0.802085	3.83211	13.6381	0	0	0	
+8.495	-0.801487	3.83439	13.6404	0	0	0	
+8.496	-0.800889	3.83666	13.6427	0	0	0	
+8.497	-0.80029	3.83892	13.6449	0	0	0	
+8.498	-0.79969	3.84116	13.6472	0	0	0	
+8.499	-0.799089	3.84338	13.6494	0	0	0	
+8.5	-0.798487	3.84559	13.6516	0	0	0	
+8.501	-0.797885	3.84778	13.6538	0	0	0	
+8.502	-0.797281	3.84996	13.656	0	0	0	
+8.503	-0.796677	3.85212	13.6581	0	0	0	
+8.504	-0.796073	3.85427	13.6603	0	0	0	
+8.505	-0.795467	3.8564	13.6624	0	0	0	
+8.506	-0.794861	3.85852	13.6645	0	0	0	
+8.507	-0.794254	3.86062	13.6666	0	0	0	
+8.508	-0.793646	3.86271	13.6687	0	0	0	
+8.509	-0.793037	3.86478	13.6708	0	0	0	
+8.51	-0.792427	3.86683	13.6728	0	0	0	
+8.511	-0.791817	3.86887	13.6749	0	0	0	
+8.512	-0.791206	3.8709	13.6769	0	0	0	
+8.513	-0.790594	3.8729	13.6789	0	0	0	
+8.514	-0.789981	3.8749	13.6809	0	0	0	
+8.515	-0.789367	3.87687	13.6829	0	0	0	
+8.516	-0.788753	3.87884	13.6848	0	0	0	
+8.517	-0.788138	3.88078	13.6868	0	0	0	
+8.518	-0.787522	3.88271	13.6887	0	0	0	
+8.519	-0.786905	3.88463	13.6906	0	0	0	
+8.52	-0.786288	3.88653	13.6925	0	0	0	
+8.521	-0.78567	3.88841	13.6944	0	0	0	
+8.522	-0.785051	3.89028	13.6963	0	0	0	
+8.523	-0.784431	3.89213	13.6981	0	0	0	
+8.524	-0.78381	3.89397	13.7	0	0	0	
+8.525	-0.783189	3.89579	13.7018	0	0	0	
+8.526	-0.782567	3.8976	13.7036	0	0	0	
+8.527	-0.781944	3.89939	13.7054	0	0	0	
+8.528	-0.78132	3.90117	13.7072	0	0	0	
+8.529	-0.780695	3.90293	13.7089	0	0	0	
+8.53	-0.78007	3.90467	13.7107	0	0	0	
+8.531	-0.779444	3.9064	13.7124	0	0	0	
+8.532	-0.778817	3.90811	13.7141	0	0	0	
+8.533	-0.77819	3.90981	13.7158	0	0	0	
+8.534	-0.777561	3.91149	13.7175	0	0	0	
+8.535	-0.776932	3.91315	13.7192	0	0	0	
+8.536	-0.776302	3.91481	13.7208	0	0	0	
+8.537	-0.775671	3.91644	13.7224	0	0	0	
+8.538	-0.77504	3.91806	13.7241	0	0	0	
+8.539	-0.774407	3.91966	13.7257	0	0	0	
+8.54	-0.773774	3.92125	13.7272	0	0	0	
+8.541	-0.773141	3.92282	13.7288	0	0	0	
+8.542	-0.772506	3.92438	13.7304	0	0	0	
+8.543	-0.77187	3.92592	13.7319	0	0	0	
+8.544	-0.771234	3.92744	13.7334	0	0	0	
+8.545	-0.770597	3.92895	13.735	0	0	0	
+8.546	-0.76996	3.93044	13.7364	0	0	0	
+8.547	-0.769321	3.93192	13.7379	0	0	0	
+8.548	-0.768682	3.93338	13.7394	0	0	0	
+8.549	-0.768042	3.93483	13.7408	0	0	0	
+8.55	-0.767401	3.93626	13.7423	0	0	0	
+8.551	-0.76676	3.93767	13.7437	0	0	0	
+8.552	-0.766117	3.93907	13.7451	0	0	0	
+8.553	-0.765474	3.94046	13.7465	0	0	0	
+8.554	-0.76483	3.94182	13.7478	0	0	0	
+8.555	-0.764186	3.94318	13.7492	0	0	0	
+8.556	-0.76354	3.94451	13.7505	0	0	0	
+8.557	-0.762894	3.94583	13.7518	0	0	0	
+8.558	-0.762247	3.94714	13.7531	0	0	0	
+8.559	-0.7616	3.94842	13.7544	0	0	0	
+8.56	-0.760951	3.9497	13.7557	0	0	0	
+8.561	-0.760302	3.95095	13.757	0	0	0	
+8.562	-0.759652	3.95219	13.7582	0	0	0	
+8.563	-0.759001	3.95342	13.7594	0	0	0	
+8.564	-0.75835	3.95463	13.7606	0	0	0	
+8.565	-0.757698	3.95582	13.7618	0	0	0	
+8.566	-0.757045	3.957	13.763	0	0	0	
+8.567	-0.756391	3.95816	13.7642	0	0	0	
+8.568	-0.755736	3.95931	13.7653	0	0	0	
+8.569	-0.755081	3.96044	13.7664	0	0	0	
+8.57	-0.754425	3.96155	13.7676	0	0	0	
+8.571	-0.753768	3.96265	13.7687	0	0	0	
+8.572	-0.753111	3.96373	13.7697	0	0	0	
+8.573	-0.752453	3.9648	13.7708	0	0	0	
+8.574	-0.751794	3.96585	13.7719	0	0	0	
+8.575	-0.751134	3.96689	13.7729	0	0	0	
+8.576	-0.750473	3.96791	13.7739	0	0	0	
+8.577	-0.749812	3.96891	13.7749	0	0	0	
+8.578	-0.74915	3.9699	13.7759	0	0	0	
+8.579	-0.748487	3.97087	13.7769	0	0	0	
+8.58	-0.747824	3.97183	13.7778	0	0	0	
+8.581	-0.747159	3.97277	13.7788	0	0	0	
+8.582	-0.746494	3.97369	13.7797	0	0	0	
+8.583	-0.745829	3.9746	13.7806	0	0	0	
+8.584	-0.745162	3.97549	13.7815	0	0	0	
+8.585	-0.744495	3.97637	13.7824	0	0	0	
+8.586	-0.743827	3.97723	13.7832	0	0	0	
+8.587	-0.743158	3.97807	13.7841	0	0	0	
+8.588	-0.742489	3.9789	13.7849	0	0	0	
+8.589	-0.741818	3.97971	13.7857	0	0	0	
+8.59	-0.741147	3.98051	13.7865	0	0	0	
+8.591	-0.740476	3.98129	13.7873	0	0	0	
+8.592	-0.739803	3.98205	13.7881	0	0	0	
+8.593	-0.73913	3.9828	13.7888	0	0	0	
+8.594	-0.738456	3.98354	13.7895	0	0	0	
+8.595	-0.737782	3.98425	13.7903	0	0	0	
+8.596	-0.737106	3.98495	13.791	0	0	0	
+8.597	-0.73643	3.98564	13.7916	0	0	0	
+8.598	-0.735753	3.98631	13.7923	0	0	0	
+8.599	-0.735075	3.98696	13.793	0	0	0	
+8.6	-0.734397	3.9876	13.7936	0	0	0	
+8.601	-0.733718	3.98822	13.7942	0	0	0	
+8.602	-0.733038	3.98883	13.7948	0	0	0	
+8.603	-0.732358	3.98942	13.7954	0	0	0	
+8.604	-0.731676	3.98999	13.796	0	0	0	
+8.605	-0.730994	3.99055	13.7965	0	0	0	
+8.606	-0.730312	3.99109	13.7971	0	0	0	
+8.607	-0.729628	3.99162	13.7976	0	0	0	
+8.608	-0.728944	3.99213	13.7981	0	0	0	
+8.609	-0.728259	3.99262	13.7986	0	0	0	
+8.61	-0.727573	3.9931	13.7991	0	0	0	
+8.611	-0.726887	3.99356	13.7996	0	0	0	
+8.612	-0.7262	3.994	13.8	0	0	0	
+8.613	-0.725512	3.99443	13.8004	0	0	0	
+8.614	-0.724823	3.99485	13.8008	0	0	0	
+8.615	-0.724134	3.99525	13.8012	0	0	0	
+8.616	-0.723444	3.99563	13.8016	0	0	0	
+8.617	-0.722753	3.99599	13.802	0	0	0	
+8.618	-0.722062	3.99634	13.8023	0	0	0	
+8.619	-0.72137	3.99668	13.8027	0	0	0	
+8.62	-0.720677	3.997	13.803	0	0	0	
+8.621	-0.719983	3.9973	13.8033	0	0	0	
+8.622	-0.719289	3.99758	13.8036	0	0	0	
+8.623	-0.718594	3.99785	13.8039	0	0	0	
+8.624	-0.717898	3.99811	13.8041	0	0	0	
+8.625	-0.717201	3.99835	13.8043	0	0	0	
+8.626	-0.716504	3.99857	13.8046	0	0	0	
+8.627	-0.715806	3.99877	13.8048	0	0	0	
+8.628	-0.715108	3.99896	13.805	0	0	0	
+8.629	-0.714408	3.99914	13.8051	0	0	0	
+8.63	-0.713708	3.9993	13.8053	0	0	0	
+8.631	-0.713007	3.99944	13.8054	0	0	0	
+8.632	-0.712306	3.99956	13.8056	0	0	0	
+8.633	-0.711604	3.99967	13.8057	0	0	0	
+8.634	-0.710901	3.99977	13.8058	0	0	0	
+8.635	-0.710197	3.99985	13.8058	0	0	0	
+8.636	-0.709493	3.99991	13.8059	0	0	0	
+8.637	-0.708788	3.99995	13.806	0	0	0	
+8.638	-0.708082	3.99998	13.806	0	0	0	
+8.639	-0.707375	4	13.806	0	0	0	
+8.64	-0.706668	4	13.806	0	0	0	
+8.641	-0.70596	3.99998	13.806	0	0	0	
+8.642	-0.705252	3.99995	13.8059	0	0	0	
+8.643	-0.704542	3.9999	13.8059	0	0	0	
+8.644	-0.703832	3.99983	13.8058	0	0	0	
+8.645	-0.703122	3.99975	13.8057	0	0	0	
+8.646	-0.70241	3.99965	13.8056	0	0	0	
+8.647	-0.701698	3.99954	13.8055	0	0	0	
+8.648	-0.700985	3.99941	13.8054	0	0	0	
+8.649	-0.700272	3.99926	13.8053	0	0	0	
+8.65	-0.699557	3.9991	13.8051	0	0	0	
+8.651	-0.698843	3.99892	13.8049	0	0	0	
+8.652	-0.698127	3.99873	13.8047	0	0	0	
+8.653	-0.697411	3.99852	13.8045	0	0	0	
+8.654	-0.696694	3.99829	13.8043	0	0	0	
+8.655	-0.695976	3.99805	13.804	0	0	0	
+8.656	-0.695257	3.99779	13.8038	0	0	0	
+8.657	-0.694538	3.99752	13.8035	0	0	0	
+8.658	-0.693818	3.99723	13.8032	0	0	0	
+8.659	-0.693098	3.99692	13.8029	0	0	0	
+8.66	-0.692377	3.9966	13.8026	0	0	0	
+8.661	-0.691655	3.99626	13.8023	0	0	0	
+8.662	-0.690932	3.99591	13.8019	0	0	0	
+8.663	-0.690209	3.99554	13.8015	0	0	0	
+8.664	-0.689485	3.99515	13.8012	0	0	0	
+8.665	-0.68876	3.99475	13.8007	0	0	0	
+8.666	-0.688035	3.99433	13.8003	0	0	0	
+8.667	-0.687309	3.9939	13.7999	0	0	0	
+8.668	-0.686582	3.99345	13.7994	0	0	0	
+8.669	-0.685855	3.99298	13.799	0	0	0	
+8.67	-0.685127	3.9925	13.7985	0	0	0	
+8.671	-0.684398	3.992	13.798	0	0	0	
+8.672	-0.683669	3.99149	13.7975	0	0	0	
+8.673	-0.682939	3.99096	13.797	0	0	0	
+8.674	-0.682208	3.99042	13.7964	0	0	0	
+8.675	-0.681476	3.98985	13.7959	0	0	0	
+8.676	-0.680744	3.98928	13.7953	0	0	0	
+8.677	-0.680011	3.98868	13.7947	0	0	0	
+8.678	-0.679278	3.98807	13.7941	0	0	0	
+8.679	-0.678543	3.98745	13.7934	0	0	0	
+8.68	-0.677809	3.98681	13.7928	0	0	0	
+8.681	-0.677073	3.98615	13.7922	0	0	0	
+8.682	-0.676337	3.98548	13.7915	0	0	0	
+8.683	-0.6756	3.98479	13.7908	0	0	0	
+8.684	-0.674862	3.98408	13.7901	0	0	0	
+8.685	-0.674124	3.98336	13.7894	0	0	0	
+8.686	-0.673385	3.98263	13.7886	0	0	0	
+8.687	-0.672645	3.98187	13.7879	0	0	0	
+8.688	-0.671905	3.9811	13.7871	0	0	0	
+8.689	-0.671164	3.98032	13.7863	0	0	0	
+8.69	-0.670422	3.97952	13.7855	0	0	0	
+8.691	-0.66968	3.9787	13.7847	0	0	0	
+8.692	-0.668937	3.97787	13.7839	0	0	0	
+8.693	-0.668193	3.97702	13.783	0	0	0	
+8.694	-0.667449	3.97616	13.7822	0	0	0	
+8.695	-0.666704	3.97528	13.7813	0	0	0	
+8.696	-0.665959	3.97438	13.7804	0	0	0	
+8.697	-0.665212	3.97347	13.7795	0	0	0	
+8.698	-0.664465	3.97254	13.7785	0	0	0	
+8.699	-0.663718	3.9716	13.7776	0	0	0	
+8.7	-0.662969	3.97064	13.7766	0	0	0	
+8.701	-0.66222	3.96966	13.7757	0	0	0	
+8.702	-0.661471	3.96867	13.7747	0	0	0	
+8.703	-0.66072	3.96766	13.7737	0	0	0	
+8.704	-0.659969	3.96664	13.7726	0	0	0	
+8.705	-0.659218	3.9656	13.7716	0	0	0	
+8.706	-0.658465	3.96455	13.7705	0	0	0	
+8.707	-0.657713	3.96348	13.7695	0	0	0	
+8.708	-0.656959	3.96239	13.7684	0	0	0	
+8.709	-0.656205	3.96129	13.7673	0	0	0	
+8.71	-0.65545	3.96017	13.7662	0	0	0	
+8.711	-0.654694	3.95903	13.765	0	0	0	
+8.712	-0.653938	3.95788	13.7639	0	0	0	
+8.713	-0.653181	3.95672	13.7627	0	0	0	
+8.714	-0.652424	3.95554	13.7615	0	0	0	
+8.715	-0.651665	3.95434	13.7603	0	0	0	
+8.716	-0.650907	3.95313	13.7591	0	0	0	
+8.717	-0.650147	3.9519	13.7579	0	0	0	
+8.718	-0.649387	3.95065	13.7567	0	0	0	
+8.719	-0.648626	3.94939	13.7554	0	0	0	
+8.72	-0.647865	3.94812	13.7541	0	0	0	
+8.721	-0.647103	3.94682	13.7528	0	0	0	
+8.722	-0.64634	3.94552	13.7515	0	0	0	
+8.723	-0.645577	3.94419	13.7502	0	0	0	
+8.724	-0.644813	3.94285	13.7489	0	0	0	
+8.725	-0.644048	3.9415	13.7475	0	0	0	
+8.726	-0.643283	3.94013	13.7461	0	0	0	
+8.727	-0.642517	3.93874	13.7447	0	0	0	
+8.728	-0.64175	3.93734	13.7433	0	0	0	
+8.729	-0.640983	3.93592	13.7419	0	0	0	
+8.73	-0.640215	3.93448	13.7405	0	0	0	
+8.731	-0.639446	3.93303	13.739	0	0	0	
+8.732	-0.638677	3.93157	13.7376	0	0	0	
+8.733	-0.637907	3.93009	13.7361	0	0	0	
+8.734	-0.637137	3.92859	13.7346	0	0	0	
+8.735	-0.636366	3.92708	13.7331	0	0	0	
+8.736	-0.635594	3.92555	13.7315	0	0	0	
+8.737	-0.634822	3.924	13.73	0	0	0	
+8.738	-0.634049	3.92244	13.7284	0	0	0	
+8.739	-0.633275	3.92087	13.7269	0	0	0	
+8.74	-0.632501	3.91928	13.7253	0	0	0	
+8.741	-0.631726	3.91767	13.7237	0	0	0	
+8.742	-0.630951	3.91605	13.722	0	0	0	
+8.743	-0.630175	3.91441	13.7204	0	0	0	
+8.744	-0.629398	3.91276	13.7188	0	0	0	
+8.745	-0.62862	3.91109	13.7171	0	0	0	
+8.746	-0.627842	3.9094	13.7154	0	0	0	
+8.747	-0.627064	3.9077	13.7137	0	0	0	
+8.748	-0.626284	3.90598	13.712	0	0	0	
+8.749	-0.625504	3.90425	13.7103	0	0	0	
+8.75	-0.624724	3.9025	13.7085	0	0	0	
+8.751	-0.623943	3.90074	13.7067	0	0	0	
+8.752	-0.623161	3.89896	13.705	0	0	0	
+8.753	-0.622379	3.89717	13.7032	0	0	0	
+8.754	-0.621596	3.89536	13.7014	0	0	0	
+8.755	-0.620812	3.89353	13.6995	0	0	0	
+8.756	-0.620028	3.89169	13.6977	0	0	0	
+8.757	-0.619243	3.88983	13.6958	0	0	0	
+8.758	-0.618457	3.88796	13.694	0	0	0	
+8.759	-0.617671	3.88607	13.6921	0	0	0	
+8.76	-0.616884	3.88417	13.6902	0	0	0	
+8.761	-0.616097	3.88225	13.6883	0	0	0	
+8.762	-0.615309	3.88032	13.6863	0	0	0	
+8.763	-0.61452	3.87837	13.6844	0	0	0	
+8.764	-0.613731	3.8764	13.6824	0	0	0	
+8.765	-0.612941	3.87442	13.6804	0	0	0	
+8.766	-0.612151	3.87242	13.6784	0	0	0	
+8.767	-0.61136	3.87041	13.6764	0	0	0	
+8.768	-0.610568	3.86838	13.6744	0	0	0	
+8.769	-0.609776	3.86634	13.6723	0	0	0	
+8.77	-0.608983	3.86428	13.6703	0	0	0	
+8.771	-0.60819	3.86221	13.6682	0	0	0	
+8.772	-0.607396	3.86012	13.6661	0	0	0	
+8.773	-0.606601	3.85801	13.664	0	0	0	
+8.774	-0.605806	3.85589	13.6619	0	0	0	
+8.775	-0.60501	3.85376	13.6598	0	0	0	
+8.776	-0.604213	3.85161	13.6576	0	0	0	
+8.777	-0.603416	3.84944	13.6554	0	0	0	
+8.778	-0.602618	3.84726	13.6533	0	0	0	
+8.779	-0.60182	3.84506	13.6511	0	0	0	
+8.78	-0.601021	3.84285	13.6488	0	0	0	
+8.781	-0.600221	3.84062	13.6466	0	0	0	
+8.782	-0.599421	3.83838	13.6444	0	0	0	
+8.783	-0.598621	3.83612	13.6421	0	0	0	
+8.784	-0.597819	3.83384	13.6398	0	0	0	
+8.785	-0.597017	3.83155	13.6376	0	0	0	
+8.786	-0.596215	3.82925	13.6352	0	0	0	
+8.787	-0.595412	3.82693	13.6329	0	0	0	
+8.788	-0.594608	3.82459	13.6306	0	0	0	
+8.789	-0.593804	3.82224	13.6282	0	0	0	
+8.79	-0.592999	3.81988	13.6259	0	0	0	
+8.791	-0.592193	3.8175	13.6235	0	0	0	
+8.792	-0.591387	3.8151	13.6211	0	0	0	
+8.793	-0.59058	3.81269	13.6187	0	0	0	
+8.794	-0.589773	3.81026	13.6163	0	0	0	
+8.795	-0.588965	3.80782	13.6138	0	0	0	
+8.796	-0.588157	3.80536	13.6114	0	0	0	
+8.797	-0.587348	3.80289	13.6089	0	0	0	
+8.798	-0.586538	3.8004	13.6064	0	0	0	
+8.799	-0.585728	3.7979	13.6039	0	0	0	
+8.8	-0.584917	3.79538	13.6014	0	0	0	
+8.801	-0.584106	3.79284	13.5988	0	0	0	
+8.802	-0.583294	3.7903	13.5963	0	0	0	
+8.803	-0.582481	3.78773	13.5937	0	0	0	
+8.804	-0.581668	3.78515	13.5912	0	0	0	
+8.805	-0.580854	3.78256	13.5886	0	0	0	
+8.806	-0.58004	3.77995	13.5859	0	0	0	
+8.807	-0.579225	3.77732	13.5833	0	0	0	
+8.808	-0.57841	3.77469	13.5807	0	0	0	
+8.809	-0.577594	3.77203	13.578	0	0	0	
+8.81	-0.576777	3.76936	13.5754	0	0	0	
+8.811	-0.57596	3.76668	13.5727	0	0	0	
+8.812	-0.575142	3.76398	13.57	0	0	0	
+8.813	-0.574324	3.76126	13.5673	0	0	0	
+8.814	-0.573505	3.75853	13.5645	0	0	0	
+8.815	-0.572685	3.75579	13.5618	0	0	0	
+8.816	-0.571865	3.75303	13.559	0	0	0	
+8.817	-0.571045	3.75025	13.5563	0	0	0	
+8.818	-0.570224	3.74746	13.5535	0	0	0	
+8.819	-0.569402	3.74466	13.5507	0	0	0	
+8.82	-0.568579	3.74184	13.5478	0	0	0	
+8.821	-0.567757	3.739	13.545	0	0	0	
+8.822	-0.566933	3.73615	13.5422	0	0	0	
+8.823	-0.566109	3.73329	13.5393	0	0	0	
+8.824	-0.565284	3.73041	13.5364	0	0	0	
+8.825	-0.564459	3.72751	13.5335	0	0	0	
+8.826	-0.563633	3.7246	13.5306	0	0	0	
+8.827	-0.562807	3.72168	13.5277	0	0	0	
+8.828	-0.56198	3.71874	13.5247	0	0	0	
+8.829	-0.561153	3.71578	13.5218	0	0	0	
+8.83	-0.560325	3.71282	13.5188	0	0	0	
+8.831	-0.559496	3.70983	13.5158	0	0	0	
+8.832	-0.558667	3.70683	13.5128	0	0	0	
+8.833	-0.557838	3.70382	13.5098	0	0	0	
+8.834	-0.557007	3.70079	13.5068	0	0	0	
+8.835	-0.556177	3.69775	13.5037	0	0	0	
+8.836	-0.555345	3.69469	13.5007	0	0	0	
+8.837	-0.554513	3.69162	13.4976	0	0	0	
+8.838	-0.553681	3.68853	13.4945	0	0	0	
+8.839	-0.552848	3.68543	13.4914	0	0	0	
+8.84	-0.552014	3.68231	13.4883	0	0	0	
+8.841	-0.55118	3.67918	13.4852	0	0	0	
+8.842	-0.550345	3.67603	13.482	0	0	0	
+8.843	-0.54951	3.67287	13.4789	0	0	0	
+8.844	-0.548675	3.66969	13.4757	0	0	0	
+8.845	-0.547838	3.6665	13.4725	0	0	0	
+8.846	-0.547001	3.6633	13.4693	0	0	0	
+8.847	-0.546164	3.66008	13.4661	0	0	0	
+8.848	-0.545326	3.65684	13.4628	0	0	0	
+8.849	-0.544487	3.65359	13.4596	0	0	0	
+8.85	-0.543648	3.65033	13.4563	0	0	0	
+8.851	-0.542809	3.64705	13.4531	0	0	0	
+8.852	-0.541969	3.64376	13.4498	0	0	0	
+8.853	-0.541128	3.64045	13.4465	0	0	0	
+8.854	-0.540287	3.63713	13.4431	0	0	0	
+8.855	-0.539445	3.63379	13.4398	0	0	0	
+8.856	-0.538603	3.63044	13.4364	0	0	0	
+8.857	-0.53776	3.62707	13.4331	0	0	0	
+8.858	-0.536917	3.62369	13.4297	0	0	0	
+8.859	-0.536073	3.6203	13.4263	0	0	0	
+8.86	-0.535228	3.61689	13.4229	0	0	0	
+8.861	-0.534383	3.61347	13.4195	0	0	0	
+8.862	-0.533538	3.61003	13.416	0	0	0	
+8.863	-0.532692	3.60658	13.4126	0	0	0	
+8.864	-0.531845	3.60311	13.4091	0	0	0	
+8.865	-0.530998	3.59963	13.4056	0	0	0	
+8.866	-0.53015	3.59613	13.4021	0	0	0	
+8.867	-0.529302	3.59262	13.3986	0	0	0	
+8.868	-0.528454	3.5891	13.3951	0	0	0	
+8.869	-0.527604	3.58556	13.3916	0	0	0	
+8.87	-0.526755	3.582	13.388	0	0	0	
+8.871	-0.525904	3.57844	13.3844	0	0	0	
+8.872	-0.525053	3.57485	13.3809	0	0	0	
+8.873	-0.524202	3.57126	13.3773	0	0	0	
+8.874	-0.52335	3.56765	13.3736	0	0	0	
+8.875	-0.522498	3.56402	13.37	0	0	0	
+8.876	-0.521645	3.56038	13.3664	0	0	0	
+8.877	-0.520792	3.55673	13.3627	0	0	0	
+8.878	-0.519938	3.55306	13.3591	0	0	0	
+8.879	-0.519083	3.54938	13.3554	0	0	0	
+8.88	-0.518228	3.54569	13.3517	0	0	0	
+8.881	-0.517373	3.54198	13.348	0	0	0	
+8.882	-0.516517	3.53825	13.3443	0	0	0	
+8.883	-0.51566	3.53451	13.3405	0	0	0	
+8.884	-0.514803	3.53076	13.3368	0	0	0	
+8.885	-0.513946	3.52699	13.333	0	0	0	
+8.886	-0.513087	3.52321	13.3292	0	0	0	
+8.887	-0.512229	3.51942	13.3254	0	0	0	
+8.888	-0.51137	3.51561	13.3216	0	0	0	
+8.889	-0.51051	3.51179	13.3178	0	0	0	
+8.89	-0.50965	3.50795	13.3139	0	0	0	
+8.891	-0.508789	3.5041	13.3101	0	0	0	
+8.892	-0.507928	3.50023	13.3062	0	0	0	
+8.893	-0.507067	3.49635	13.3024	0	0	0	
+8.894	-0.506204	3.49246	13.2985	0	0	0	
+8.895	-0.505342	3.48855	13.2946	0	0	0	
+8.896	-0.504479	3.48463	13.2906	0	0	0	
+8.897	-0.503615	3.4807	13.2867	0	0	0	
+8.898	-0.502751	3.47675	13.2827	0	0	0	
+8.899	-0.501886	3.47279	13.2788	0	0	0	
+8.9	-0.501021	3.46881	13.2748	0	0	0	
+8.901	-0.500155	3.46482	13.2708	0	0	0	
+8.902	-0.499289	3.46081	13.2668	0	0	0	
+8.903	-0.498422	3.4568	13.2628	0	0	0	
+8.904	-0.497555	3.45276	13.2588	0	0	0	
+8.905	-0.496687	3.44872	13.2547	0	0	0	
+8.906	-0.495819	3.44466	13.2507	0	0	0	
+8.907	-0.494951	3.44058	13.2466	0	0	0	
+8.908	-0.494081	3.4365	13.2425	0	0	0	
+8.909	-0.493212	3.4324	13.2384	0	0	0	
+8.91	-0.492342	3.42828	13.2343	0	0	0	
+8.911	-0.491471	3.42415	13.2302	0	0	0	
+8.912	-0.4906	3.42001	13.226	0	0	0	
+8.913	-0.489728	3.41585	13.2219	0	0	0	
+8.914	-0.488856	3.41169	13.2177	0	0	0	
+8.915	-0.487983	3.4075	13.2135	0	0	0	
+8.916	-0.48711	3.40331	13.2093	0	0	0	
+8.917	-0.486237	3.39909	13.2051	0	0	0	
+8.918	-0.485363	3.39487	13.2009	0	0	0	
+8.919	-0.484488	3.39063	13.1966	0	0	0	
+8.92	-0.483613	3.38638	13.1924	0	0	0	
+8.921	-0.482738	3.38212	13.1881	0	0	0	
+8.922	-0.481862	3.37784	13.1838	0	0	0	
+8.923	-0.480985	3.37355	13.1795	0	0	0	
+8.924	-0.480108	3.36924	13.1752	0	0	0	
+8.925	-0.479231	3.36492	13.1709	0	0	0	
+8.926	-0.478353	3.36059	13.1666	0	0	0	
+8.927	-0.477474	3.35625	13.1622	0	0	0	
+8.928	-0.476595	3.35189	13.1579	0	0	0	
+8.929	-0.475716	3.34751	13.1535	0	0	0	
+8.93	-0.474836	3.34313	13.1491	0	0	0	
+8.931	-0.473956	3.33873	13.1447	0	0	0	
+8.932	-0.473075	3.33432	13.1403	0	0	0	
+8.933	-0.472194	3.32989	13.1359	0	0	0	
+8.934	-0.471312	3.32545	13.1315	0	0	0	
+8.935	-0.47043	3.321	13.127	0	0	0	
+8.936	-0.469547	3.31653	13.1225	0	0	0	
+8.937	-0.468664	3.31205	13.1181	0	0	0	
+8.938	-0.467781	3.30756	13.1136	0	0	0	
+8.939	-0.466896	3.30306	13.1091	0	0	0	
+8.94	-0.466012	3.29854	13.1045	0	0	0	
+8.941	-0.465127	3.29401	13.1	0	0	0	
+8.942	-0.464241	3.28946	13.0955	0	0	0	
+8.943	-0.463355	3.2849	13.0909	0	0	0	
+8.944	-0.462469	3.28033	13.0863	0	0	0	
+8.945	-0.461582	3.27575	13.0817	0	0	0	
+8.946	-0.460695	3.27115	13.0771	0	0	0	
+8.947	-0.459807	3.26654	13.0725	0	0	0	
+8.948	-0.458919	3.26192	13.0679	0	0	0	
+8.949	-0.45803	3.25728	13.0633	0	0	0	
+8.95	-0.457141	3.25263	13.0586	0	0	0	
+8.951	-0.456251	3.24797	13.054	0	0	0	
+8.952	-0.455361	3.24329	13.0493	0	0	0	
+8.953	-0.454471	3.2386	13.0446	0	0	0	
+8.954	-0.45358	3.2339	13.0399	0	0	0	
+8.955	-0.452688	3.22918	13.0352	0	0	0	
+8.956	-0.451796	3.22446	13.0305	0	0	0	
+8.957	-0.450904	3.21972	13.0257	0	0	0	
+8.958	-0.450011	3.21496	13.021	0	0	0	
+8.959	-0.449118	3.2102	13.0162	0	0	0	
+8.96	-0.448224	3.20542	13.0114	0	0	0	
+8.961	-0.44733	3.20063	13.0066	0	0	0	
+8.962	-0.446436	3.19582	13.0018	0	0	0	
+8.963	-0.445541	3.191	12.997	0	0	0	
+8.964	-0.444645	3.18617	12.9922	0	0	0	
+8.965	-0.443749	3.18133	12.9873	0	0	0	
+8.966	-0.442853	3.17647	12.9825	0	0	0	
+8.967	-0.441956	3.17161	12.9776	0	0	0	
+8.968	-0.441059	3.16672	12.9727	0	0	0	
+8.969	-0.440161	3.16183	12.9678	0	0	0	
+8.97	-0.439263	3.15692	12.9629	0	0	0	
+8.971	-0.438364	3.15201	12.958	0	0	0	
+8.972	-0.437465	3.14707	12.9531	0	0	0	
+8.973	-0.436566	3.14213	12.9481	0	0	0	
+8.974	-0.435666	3.13717	12.9432	0	0	0	
+8.975	-0.434766	3.1322	12.9382	0	0	0	
+8.976	-0.433865	3.12722	12.9332	0	0	0	
+8.977	-0.432964	3.12223	12.9282	0	0	0	
+8.978	-0.432062	3.11722	12.9232	0	0	0	
+8.979	-0.43116	3.1122	12.9182	0	0	0	
+8.98	-0.430257	3.10717	12.9132	0	0	0	
+8.981	-0.429355	3.10212	12.9081	0	0	0	
+8.982	-0.428451	3.09707	12.9031	0	0	0	
+8.983	-0.427547	3.092	12.898	0	0	0	
+8.984	-0.426643	3.08692	12.8929	0	0	0	
+8.985	-0.425739	3.08182	12.8878	0	0	0	
+8.986	-0.424834	3.07672	12.8827	0	0	0	
+8.987	-0.423928	3.0716	12.8776	0	0	0	
+8.988	-0.423022	3.06647	12.8725	0	0	0	
+8.989	-0.422116	3.06133	12.8673	0	0	0	
+8.99	-0.421209	3.05617	12.8622	0	0	0	
+8.991	-0.420302	3.051	12.857	0	0	0	
+8.992	-0.419394	3.04582	12.8518	0	0	0	
+8.993	-0.418486	3.04063	12.8466	0	0	0	
+8.994	-0.417578	3.03543	12.8414	0	0	0	
+8.995	-0.416669	3.03021	12.8362	0	0	0	
+8.996	-0.41576	3.02498	12.831	0	0	0	
+8.997	-0.41485	3.01974	12.8257	0	0	0	
+8.998	-0.41394	3.01449	12.8205	0	0	0	
+8.999	-0.413029	3.00923	12.8152	0	0	0	
+9	-0.412118	3.00395	12.8099	0	0	0	
+9.001	-0.411207	2.99866	12.8047	0	0	0	
+9.002	-0.410295	2.99336	12.7994	0	0	0	
+9.003	-0.409383	2.98805	12.794	0	0	0	
+9.004	-0.408471	2.98272	12.7887	0	0	0	
+9.005	-0.407558	2.97739	12.7834	0	0	0	
+9.006	-0.406644	2.97204	12.778	0	0	0	
+9.007	-0.405731	2.96668	12.7727	0	0	0	
+9.008	-0.404816	2.96131	12.7673	0	0	0	
+9.009	-0.403902	2.95592	12.7619	0	0	0	
+9.01	-0.402987	2.95053	12.7565	0	0	0	
+9.011	-0.402071	2.94512	12.7511	0	0	0	
+9.012	-0.401156	2.9397	12.7457	0	0	0	
+9.013	-0.400239	2.93427	12.7403	0	0	0	
+9.014	-0.399323	2.92883	12.7348	0	0	0	
+9.015	-0.398406	2.92337	12.7294	0	0	0	
+9.016	-0.397488	2.9179	12.7239	0	0	0	
+9.017	-0.39657	2.91243	12.7184	0	0	0	
+9.018	-0.395652	2.90694	12.7129	0	0	0	
+9.019	-0.394734	2.90144	12.7074	0	0	0	
+9.02	-0.393815	2.89592	12.7019	0	0	0	
+9.021	-0.392895	2.8904	12.6964	0	0	0	
+9.022	-0.391976	2.88486	12.6909	0	0	0	
+9.023	-0.391055	2.87932	12.6853	0	0	0	
+9.024	-0.390135	2.87376	12.6798	0	0	0	
+9.025	-0.389214	2.86819	12.6742	0	0	0	
+9.026	-0.388292	2.8626	12.6686	0	0	0	
+9.027	-0.387371	2.85701	12.663	0	0	0	
+9.028	-0.386449	2.85141	12.6574	0	0	0	
+9.029	-0.385526	2.84579	12.6518	0	0	0	
+9.03	-0.384603	2.84016	12.6462	0	0	0	
+9.031	-0.38368	2.83452	12.6405	0	0	0	
+9.032	-0.382756	2.82887	12.6349	0	0	0	
+9.033	-0.381832	2.82321	12.6292	0	0	0	
+9.034	-0.380908	2.81754	12.6235	0	0	0	
+9.035	-0.379983	2.81185	12.6179	0	0	0	
+9.036	-0.379058	2.80616	12.6122	0	0	0	
+9.037	-0.378132	2.80045	12.6065	0	0	0	
+9.038	-0.377206	2.79473	12.6007	0	0	0	
+9.039	-0.37628	2.78901	12.595	0	0	0	
+9.04	-0.375353	2.78327	12.5893	0	0	0	
+9.041	-0.374426	2.77751	12.5835	0	0	0	
+9.042	-0.373499	2.77175	12.5778	0	0	0	
+9.043	-0.372571	2.76598	12.572	0	0	0	
+9.044	-0.371643	2.76019	12.5662	0	0	0	
+9.045	-0.370714	2.7544	12.5604	0	0	0	
+9.046	-0.369785	2.74859	12.5546	0	0	0	
+9.047	-0.368856	2.74277	12.5488	0	0	0	
+9.048	-0.367926	2.73695	12.5429	0	0	0	
+9.049	-0.366996	2.73111	12.5371	0	0	0	
+9.05	-0.366066	2.72526	12.5313	0	0	0	
+9.051	-0.365135	2.71939	12.5254	0	0	0	
+9.052	-0.364204	2.71352	12.5195	0	0	0	
+9.053	-0.363273	2.70764	12.5136	0	0	0	
+9.054	-0.362341	2.70174	12.5077	0	0	0	
+9.055	-0.361408	2.69584	12.5018	0	0	0	
+9.056	-0.360476	2.68992	12.4959	0	0	0	
+9.057	-0.359543	2.684	12.49	0	0	0	
+9.058	-0.35861	2.67806	12.4841	0	0	0	
+9.059	-0.357676	2.67211	12.4781	0	0	0	
+9.06	-0.356742	2.66615	12.4722	0	0	0	
+9.061	-0.355807	2.66019	12.4662	0	0	0	
+9.062	-0.354873	2.65421	12.4602	0	0	0	
+9.063	-0.353938	2.64822	12.4542	0	0	0	
+9.064	-0.353002	2.64221	12.4482	0	0	0	
+9.065	-0.352066	2.6362	12.4422	0	0	0	
+9.066	-0.35113	2.63018	12.4362	0	0	0	
+9.067	-0.350194	2.62415	12.4301	0	0	0	
+9.068	-0.349257	2.61811	12.4241	0	0	0	
+9.069	-0.34832	2.61205	12.4181	0	0	0	
+9.07	-0.347382	2.60599	12.412	0	0	0	
+9.071	-0.346444	2.59991	12.4059	0	0	0	
+9.072	-0.345506	2.59383	12.3998	0	0	0	
+9.073	-0.344567	2.58773	12.3937	0	0	0	
+9.074	-0.343628	2.58163	12.3876	0	0	0	
+9.075	-0.342689	2.57551	12.3815	0	0	0	
+9.076	-0.34175	2.56939	12.3754	0	0	0	
+9.077	-0.34081	2.56325	12.3692	0	0	0	
+9.078	-0.339869	2.5571	12.3631	0	0	0	
+9.079	-0.338929	2.55095	12.3569	0	0	0	
+9.08	-0.337988	2.54478	12.3508	0	0	0	
+9.081	-0.337046	2.5386	12.3446	0	0	0	
+9.082	-0.336105	2.53241	12.3384	0	0	0	
+9.083	-0.335163	2.52622	12.3322	0	0	0	
+9.084	-0.33422	2.52001	12.326	0	0	0	
+9.085	-0.333278	2.51379	12.3198	0	0	0	
+9.086	-0.332335	2.50756	12.3136	0	0	0	
+9.087	-0.331391	2.50132	12.3073	0	0	0	
+9.088	-0.330448	2.49508	12.3011	0	0	0	
+9.089	-0.329504	2.48882	12.2948	0	0	0	
+9.09	-0.328559	2.48255	12.2886	0	0	0	
+9.091	-0.327615	2.47627	12.2823	0	0	0	
+9.092	-0.32667	2.46999	12.276	0	0	0	
+9.093	-0.325725	2.46369	12.2697	0	0	0	
+9.094	-0.324779	2.45738	12.2634	0	0	0	
+9.095	-0.323833	2.45106	12.2571	0	0	0	
+9.096	-0.322887	2.44474	12.2507	0	0	0	
+9.097	-0.32194	2.4384	12.2444	0	0	0	
+9.098	-0.320993	2.43205	12.2381	0	0	0	
+9.099	-0.320046	2.4257	12.2317	0	0	0	
+9.1	-0.319098	2.41933	12.2253	0	0	0	
+9.101	-0.31815	2.41296	12.219	0	0	0	
+9.102	-0.317202	2.40657	12.2126	0	0	0	
+9.103	-0.316254	2.40018	12.2062	0	0	0	
+9.104	-0.315305	2.39377	12.1998	0	0	0	
+9.105	-0.314356	2.38736	12.1934	0	0	0	
+9.106	-0.313406	2.38093	12.1869	0	0	0	
+9.107	-0.312457	2.3745	12.1805	0	0	0	
+9.108	-0.311506	2.36806	12.1741	0	0	0	
+9.109	-0.310556	2.36161	12.1676	0	0	0	
+9.11	-0.309605	2.35514	12.1611	0	0	0	
+9.111	-0.308654	2.34867	12.1547	0	0	0	
+9.112	-0.307703	2.34219	12.1482	0	0	0	
+9.113	-0.306751	2.3357	12.1417	0	0	0	
+9.114	-0.305799	2.3292	12.1352	0	0	0	
+9.115	-0.304847	2.32269	12.1287	0	0	0	
+9.116	-0.303895	2.31618	12.1222	0	0	0	
+9.117	-0.302942	2.30965	12.1156	0	0	0	
+9.118	-0.301989	2.30311	12.1091	0	0	0	
+9.119	-0.301035	2.29657	12.1026	0	0	0	
+9.12	-0.300081	2.29001	12.096	0	0	0	
+9.121	-0.299127	2.28345	12.0894	0	0	0	
+9.122	-0.298173	2.27688	12.0829	0	0	0	
+9.123	-0.297218	2.27029	12.0763	0	0	0	
+9.124	-0.296263	2.2637	12.0697	0	0	0	
+9.125	-0.295308	2.2571	12.0631	0	0	0	
+9.126	-0.294353	2.25049	12.0565	0	0	0	
+9.127	-0.293397	2.24388	12.0499	0	0	0	
+9.128	-0.292441	2.23725	12.0432	0	0	0	
+9.129	-0.291484	2.23061	12.0366	0	0	0	
+9.13	-0.290527	2.22397	12.03	0	0	0	
+9.131	-0.28957	2.21731	12.0233	0	0	0	
+9.132	-0.288613	2.21065	12.0167	0	0	0	
+9.133	-0.287655	2.20398	12.01	0	0	0	
+9.134	-0.286698	2.1973	12.0033	0	0	0	
+9.135	-0.285739	2.19061	11.9966	0	0	0	
+9.136	-0.284781	2.18391	11.9899	0	0	0	
+9.137	-0.283822	2.1772	11.9832	0	0	0	
+9.138	-0.282863	2.17049	11.9765	0	0	0	
+9.139	-0.281904	2.16377	11.9698	0	0	0	
+9.14	-0.280944	2.15703	11.963	0	0	0	
+9.141	-0.279984	2.15029	11.9563	0	0	0	
+9.142	-0.279024	2.14354	11.9495	0	0	0	
+9.143	-0.278064	2.13678	11.9428	0	0	0	
+9.144	-0.277103	2.13002	11.936	0	0	0	
+9.145	-0.276142	2.12324	11.9292	0	0	0	
+9.146	-0.275181	2.11646	11.9225	0	0	0	
+9.147	-0.274219	2.10966	11.9157	0	0	0	
+9.148	-0.273258	2.10286	11.9089	0	0	0	
+9.149	-0.272296	2.09605	11.9021	0	0	0	
+9.15	-0.271333	2.08923	11.8952	0	0	0	
+9.151	-0.270371	2.08241	11.8884	0	0	0	
+9.152	-0.269408	2.07557	11.8816	0	0	0	
+9.153	-0.268445	2.06873	11.8747	0	0	0	
+9.154	-0.267481	2.06188	11.8679	0	0	0	
+9.155	-0.266517	2.05502	11.861	0	0	0	
+9.156	-0.265553	2.04815	11.8542	0	0	0	
+9.157	-0.264589	2.04128	11.8473	0	0	0	
+9.158	-0.263625	2.03439	11.8404	0	0	0	
+9.159	-0.26266	2.0275	11.8335	0	0	0	
+9.16	-0.261695	2.0206	11.8266	0	0	0	
+9.161	-0.26073	2.01369	11.8197	0	0	0	
+9.162	-0.259764	2.00678	11.8128	0	0	0	
+9.163	-0.258798	1.99985	11.8059	0	0	0	
+9.164	-0.257832	1.99292	11.7989	0	0	0	
+9.165	-0.256866	1.98598	11.792	0	0	0	
+9.166	-0.255899	1.97903	11.785	0	0	0	
+9.167	-0.254933	1.97207	11.7781	0	0	0	
+9.168	-0.253965	1.96511	11.7711	0	0	0	
+9.169	-0.252998	1.95814	11.7641	0	0	0	
+9.17	-0.252031	1.95116	11.7572	0	0	0	
+9.171	-0.251063	1.94417	11.7502	0	0	0	
+9.172	-0.250095	1.93718	11.7432	0	0	0	
+9.173	-0.249126	1.93017	11.7362	0	0	0	
+9.174	-0.248158	1.92316	11.7292	0	0	0	
+9.175	-0.247189	1.91614	11.7221	0	0	0	
+9.176	-0.24622	1.90912	11.7151	0	0	0	
+9.177	-0.24525	1.90208	11.7081	0	0	0	
+9.178	-0.244281	1.89504	11.701	0	0	0	
+9.179	-0.243311	1.88799	11.694	0	0	0	
+9.18	-0.242341	1.88094	11.6869	0	0	0	
+9.181	-0.241371	1.87387	11.6799	0	0	0	
+9.182	-0.2404	1.8668	11.6728	0	0	0	
+9.183	-0.239429	1.85972	11.6657	0	0	0	
+9.184	-0.238458	1.85263	11.6586	0	0	0	
+9.185	-0.237487	1.84554	11.6515	0	0	0	
+9.186	-0.236515	1.83844	11.6444	0	0	0	
+9.187	-0.235544	1.83133	11.6373	0	0	0	
+9.188	-0.234572	1.82422	11.6302	0	0	0	
+9.189	-0.233599	1.81709	11.6231	0	0	0	
+9.19	-0.232627	1.80996	11.616	0	0	0	
+9.191	-0.231654	1.80282	11.6088	0	0	0	
+9.192	-0.230681	1.79568	11.6017	0	0	0	
+9.193	-0.229708	1.78853	11.5945	0	0	0	
+9.194	-0.228735	1.78137	11.5874	0	0	0	
+9.195	-0.227761	1.7742	11.5802	0	0	0	
+9.196	-0.226787	1.76703	11.573	0	0	0	
+9.197	-0.225813	1.75985	11.5658	0	0	0	
+9.198	-0.224839	1.75266	11.5587	0	0	0	
+9.199	-0.223865	1.74546	11.5515	0	0	0	
+9.2	-0.22289	1.73826	11.5443	0	0	0	
+9.201	-0.221915	1.73105	11.5371	0	0	0	
+9.202	-0.22094	1.72384	11.5298	0	0	0	
+9.203	-0.219964	1.71662	11.5226	0	0	0	
+9.204	-0.218989	1.70939	11.5154	0	0	0	
+9.205	-0.218013	1.70215	11.5082	0	0	0	
+9.206	-0.217037	1.69491	11.5009	0	0	0	
+9.207	-0.216061	1.68766	11.4937	0	0	0	
+9.208	-0.215084	1.6804	11.4864	0	0	0	
+9.209	-0.214107	1.67314	11.4791	0	0	0	
+9.21	-0.21313	1.66587	11.4719	0	0	0	
+9.211	-0.212153	1.65859	11.4646	0	0	0	
+9.212	-0.211176	1.65131	11.4573	0	0	0	
+9.213	-0.210198	1.64402	11.45	0	0	0	
+9.214	-0.209221	1.63672	11.4427	0	0	0	
+9.215	-0.208243	1.62942	11.4354	0	0	0	
+9.216	-0.207265	1.62211	11.4281	0	0	0	
+9.217	-0.206286	1.61479	11.4208	0	0	0	
+9.218	-0.205308	1.60747	11.4135	0	0	0	
+9.219	-0.204329	1.60014	11.4061	0	0	0	
+9.22	-0.20335	1.59281	11.3988	0	0	0	
+9.221	-0.202371	1.58547	11.3915	0	0	0	
+9.222	-0.201391	1.57812	11.3841	0	0	0	
+9.223	-0.200412	1.57076	11.3768	0	0	0	
+9.224	-0.199432	1.5634	11.3694	0	0	0	
+9.225	-0.198452	1.55604	11.362	0	0	0	
+9.226	-0.197472	1.54866	11.3547	0	0	0	
+9.227	-0.196491	1.54128	11.3473	0	0	0	
+9.228	-0.19551	1.5339	11.3399	0	0	0	
+9.229	-0.19453	1.52651	11.3325	0	0	0	
+9.23	-0.193549	1.51911	11.3251	0	0	0	
+9.231	-0.192568	1.51171	11.3177	0	0	0	
+9.232	-0.191586	1.5043	11.3103	0	0	0	
+9.233	-0.190605	1.49688	11.3029	0	0	0	
+9.234	-0.189623	1.48946	11.2955	0	0	0	
+9.235	-0.188641	1.48203	11.288	0	0	0	
+9.236	-0.187659	1.4746	11.2806	0	0	0	
+9.237	-0.186676	1.46716	11.2732	0	0	0	
+9.238	-0.185694	1.45971	11.2657	0	0	0	
+9.239	-0.184711	1.45226	11.2583	0	0	0	
+9.24	-0.183728	1.44481	11.2508	0	0	0	
+9.241	-0.182745	1.43734	11.2433	0	0	0	
+9.242	-0.181762	1.42987	11.2359	0	0	0	
+9.243	-0.180779	1.4224	11.2284	0	0	0	
+9.244	-0.179795	1.41492	11.2209	0	0	0	
+9.245	-0.178811	1.40743	11.2134	0	0	0	
+9.246	-0.177827	1.39994	11.2059	0	0	0	
+9.247	-0.176843	1.39245	11.1984	0	0	0	
+9.248	-0.175859	1.38494	11.1909	0	0	0	
+9.249	-0.174874	1.37744	11.1834	0	0	0	
+9.25	-0.173889	1.36992	11.1759	0	0	0	
+9.251	-0.172905	1.3624	11.1684	0	0	0	
+9.252	-0.17192	1.35488	11.1609	0	0	0	
+9.253	-0.170934	1.34735	11.1533	0	0	0	
+9.254	-0.169949	1.33981	11.1458	0	0	0	
+9.255	-0.168964	1.33227	11.1383	0	0	0	
+9.256	-0.167978	1.32473	11.1307	0	0	0	
+9.257	-0.166992	1.31718	11.1232	0	0	0	
+9.258	-0.166006	1.30962	11.1156	0	0	0	
+9.259	-0.16502	1.30206	11.1081	0	0	0	
+9.26	-0.164033	1.29449	11.1005	0	0	0	
+9.261	-0.163047	1.28692	11.0929	0	0	0	
+9.262	-0.16206	1.27934	11.0853	0	0	0	
+9.263	-0.161073	1.27176	11.0778	0	0	0	
+9.264	-0.160086	1.26417	11.0702	0	0	0	
+9.265	-0.159099	1.25658	11.0626	0	0	0	
+9.266	-0.158112	1.24898	11.055	0	0	0	
+9.267	-0.157124	1.24138	11.0474	0	0	0	
+9.268	-0.156137	1.23377	11.0398	0	0	0	
+9.269	-0.155149	1.22616	11.0322	0	0	0	
+9.27	-0.154161	1.21854	11.0245	0	0	0	
+9.271	-0.153173	1.21092	11.0169	0	0	0	
+9.272	-0.152184	1.20329	11.0093	0	0	0	
+9.273	-0.151196	1.19566	11.0017	0	0	0	
+9.274	-0.150207	1.18803	10.994	0	0	0	
+9.275	-0.149219	1.18038	10.9864	0	0	0	
+9.276	-0.14823	1.17274	10.9787	0	0	0	
+9.277	-0.147241	1.16509	10.9711	0	0	0	
+9.278	-0.146252	1.15743	10.9634	0	0	0	
+9.279	-0.145262	1.14977	10.9558	0	0	0	
+9.28	-0.144273	1.14211	10.9481	0	0	0	
+9.281	-0.143283	1.13444	10.9404	0	0	0	
+9.282	-0.142293	1.12676	10.9328	0	0	0	
+9.283	-0.141303	1.11909	10.9251	0	0	0	
+9.284	-0.140313	1.1114	10.9174	0	0	0	
+9.285	-0.139323	1.10372	10.9097	0	0	0	
+9.286	-0.138333	1.09602	10.902	0	0	0	
+9.287	-0.137342	1.08833	10.8943	0	0	0	
+9.288	-0.136352	1.08063	10.8866	0	0	0	
+9.289	-0.135361	1.07292	10.8789	0	0	0	
+9.29	-0.13437	1.06521	10.8712	0	0	0	
+9.291	-0.133379	1.0575	10.8635	0	0	0	
+9.292	-0.132388	1.04978	10.8558	0	0	0	
+9.293	-0.131397	1.04206	10.8481	0	0	0	
+9.294	-0.130405	1.03434	10.8403	0	0	0	
+9.295	-0.129414	1.02661	10.8326	0	0	0	
+9.296	-0.128422	1.01887	10.8249	0	0	0	
+9.297	-0.127431	1.01113	10.8171	0	0	0	
+9.298	-0.126439	1.00339	10.8094	0	0	0	
+9.299	-0.125447	0.995645	10.8016	0	0	0	
+9.3	-0.124454	0.987895	10.7939	0	0	0	
+9.301	-0.123462	0.98014	10.7861	0	0	0	
+9.302	-0.12247	0.972382	10.7784	0	0	0	
+9.303	-0.121477	0.96462	10.7706	0	0	0	
+9.304	-0.120485	0.956855	10.7629	0	0	0	
+9.305	-0.119492	0.949085	10.7551	0	0	0	
+9.306	-0.118499	0.941312	10.7473	0	0	0	
+9.307	-0.117506	0.933534	10.7395	0	0	0	
+9.308	-0.116513	0.925753	10.7318	0	0	0	
+9.309	-0.115519	0.917969	10.724	0	0	0	
+9.31	-0.114526	0.91018	10.7162	0	0	0	
+9.311	-0.113533	0.902389	10.7084	0	0	0	
+9.312	-0.112539	0.894593	10.7006	0	0	0	
+9.313	-0.111545	0.886794	10.6928	0	0	0	
+9.314	-0.110552	0.878991	10.685	0	0	0	
+9.315	-0.109558	0.871185	10.6772	0	0	0	
+9.316	-0.108564	0.863375	10.6694	0	0	0	
+9.317	-0.107569	0.855562	10.6616	0	0	0	
+9.318	-0.106575	0.847746	10.6537	0	0	0	
+9.319	-0.105581	0.839926	10.6459	0	0	0	
+9.32	-0.104586	0.832102	10.6381	0	0	0	
+9.321	-0.103592	0.824276	10.6303	0	0	0	
+9.322	-0.102597	0.816446	10.6224	0	0	0	
+9.323	-0.101602	0.808612	10.6146	0	0	0	
+9.324	-0.100607	0.800776	10.6068	0	0	0	
+9.325	-0.0996125	0.792936	10.5989	0	0	0	
+9.326	-0.0986174	0.785094	10.5911	0	0	0	
+9.327	-0.0976222	0.777248	10.5832	0	0	0	
+9.328	-0.096627	0.769398	10.5754	0	0	0	
+9.329	-0.0956316	0.761546	10.5675	0	0	0	
+9.33	-0.0946361	0.753691	10.5597	0	0	0	
+9.331	-0.0936406	0.745833	10.5518	0	0	0	
+9.332	-0.0926449	0.737972	10.544	0	0	0	
+9.333	-0.0916492	0.730108	10.5361	0	0	0	
+9.334	-0.0906533	0.722241	10.5282	0	0	0	
+9.335	-0.0896574	0.714371	10.5204	0	0	0	
+9.336	-0.0886614	0.706498	10.5125	0	0	0	
+9.337	-0.0876653	0.698622	10.5046	0	0	0	
+9.338	-0.0866691	0.690744	10.4967	0	0	0	
+9.339	-0.0856728	0.682863	10.4889	0	0	0	
+9.34	-0.0846764	0.674979	10.481	0	0	0	
+9.341	-0.08368	0.667092	10.4731	0	0	0	
+9.342	-0.0826835	0.659203	10.4652	0	0	0	
+9.343	-0.0816868	0.651311	10.4573	0	0	0	
+9.344	-0.0806901	0.643416	10.4494	0	0	0	
+9.345	-0.0796934	0.635519	10.4415	0	0	0	
+9.346	-0.0786965	0.627619	10.4336	0	0	0	
+9.347	-0.0776996	0.619717	10.4257	0	0	0	
+9.348	-0.0767026	0.611813	10.4178	0	0	0	
+9.349	-0.0757055	0.603906	10.4099	0	0	0	
+9.35	-0.0747083	0.595996	10.402	0	0	0	
+9.351	-0.073711	0.588084	10.3941	0	0	0	
+9.352	-0.0727137	0.58017	10.3862	0	0	0	
+9.353	-0.0717163	0.572253	10.3783	0	0	0	
+9.354	-0.0707189	0.564335	10.3703	0	0	0	
+9.355	-0.0697214	0.556413	10.3624	0	0	0	
+9.356	-0.0687237	0.54849	10.3545	0	0	0	
+9.357	-0.0677261	0.540565	10.3466	0	0	0	
+9.358	-0.0667283	0.532637	10.3386	0	0	0	
+9.359	-0.0657305	0.524707	10.3307	0	0	0	
+9.36	-0.0647327	0.516775	10.3228	0	0	0	
+9.361	-0.0637347	0.508841	10.3148	0	0	0	
+9.362	-0.0627367	0.500905	10.3069	0	0	0	
+9.363	-0.0617387	0.492967	10.299	0	0	0	
+9.364	-0.0607405	0.485027	10.291	0	0	0	
+9.365	-0.0597424	0.477085	10.2831	0	0	0	
+9.366	-0.0587441	0.469141	10.2751	0	0	0	
+9.367	-0.0577458	0.461196	10.2672	0	0	0	
+9.368	-0.0567475	0.453248	10.2592	0	0	0	
+9.369	-0.055749	0.445299	10.2513	0	0	0	
+9.37	-0.0547506	0.437348	10.2433	0	0	0	
+9.371	-0.053752	0.429395	10.2354	0	0	0	
+9.372	-0.0527535	0.42144	10.2274	0	0	0	
+9.373	-0.0517548	0.413484	10.2195	0	0	0	
+9.374	-0.0507561	0.405526	10.2115	0	0	0	
+9.375	-0.0497574	0.397566	10.2036	0	0	0	
+9.376	-0.0487586	0.389605	10.1956	0	0	0	
+9.377	-0.0477598	0.381642	10.1876	0	0	0	
+9.378	-0.0467609	0.373678	10.1797	0	0	0	
+9.379	-0.045762	0.365712	10.1717	0	0	0	
+9.38	-0.044763	0.357745	10.1637	0	0	0	
+9.381	-0.043764	0.349776	10.1558	0	0	0	
+9.382	-0.0427649	0.341806	10.1478	0	0	0	
+9.383	-0.0417658	0.333835	10.1398	0	0	0	
+9.384	-0.0407667	0.325862	10.1319	0	0	0	
+9.385	-0.0397675	0.317888	10.1239	0	0	0	
+9.386	-0.0387682	0.309913	10.1159	0	0	0	
+9.387	-0.037769	0.301936	10.1079	0	0	0	
+9.388	-0.0367697	0.293958	10.1	0	0	0	
+9.389	-0.0357703	0.285979	10.092	0	0	0	
+9.39	-0.034771	0.277999	10.084	0	0	0	
+9.391	-0.0337715	0.270018	10.076	0	0	0	
+9.392	-0.0327721	0.262036	10.068	0	0	0	
+9.393	-0.0317726	0.254053	10.0601	0	0	0	
+9.394	-0.0307731	0.246068	10.0521	0	0	0	
+9.395	-0.0297736	0.238083	10.0441	0	0	0	
+9.396	-0.028774	0.230097	10.0361	0	0	0	
+9.397	-0.0277744	0.222109	10.0281	0	0	0	
+9.398	-0.0267748	0.214121	10.0201	0	0	0	
+9.399	-0.0257751	0.206132	10.0121	0	0	0	
+9.4	-0.0247754	0.198143	10.0041	0	0	0	
+9.401	-0.0237757	0.190152	9.99615	0	0	0	
+9.402	-0.022776	0.182161	9.98816	0	0	0	
+9.403	-0.0217762	0.174169	9.98017	0	0	0	
+9.404	-0.0207765	0.166176	9.97218	0	0	0	
+9.405	-0.0197767	0.158182	9.96418	0	0	0	
+9.406	-0.0187769	0.150188	9.95619	0	0	0	
+9.407	-0.017777	0.142194	9.94819	0	0	0	
+9.408	-0.0167772	0.134198	9.9402	0	0	0	
+9.409	-0.0157773	0.126203	9.9322	0	0	0	
+9.41	-0.0147774	0.118206	9.92421	0	0	0	
+9.411	-0.0137775	0.11021	9.91621	0	0	0	
+9.412	-0.0127776	0.102213	9.90821	0	0	0	
+9.413	-0.0117777	0.094215	9.90021	0	0	0	
+9.414	-0.0107778	0.086217	9.89222	0	0	0	
+9.415	-0.0097778	0.0782187	9.88422	0	0	0	
+9.416	-0.00877785	0.0702201	9.87622	0	0	0	
+9.417	-0.00777788	0.0622212	9.86822	0	0	0	
+9.418	-0.00677791	0.054222	9.86022	0	0	0	
+9.419	-0.00577793	0.0462227	9.85222	0	0	0	
+9.42	-0.00477794	0.0382231	9.84422	0	0	0	
+9.421	-0.00377795	0.0302234	9.83622	0	0	0	
+9.422	-0.00277796	0.0222236	9.82822	0	0	0	
+9.423	-0.00177796	0.0142237	9.82022	0	0	0	
+9.424	-0.000777961	0.00622368	9.81222	0	0	0	
+9.425	0.000222039	-0.00177631	9.80422	0	0	0	
+9.426	0.00122204	-0.0097763	9.79622	0	0	0	
+9.427	0.00222204	-0.0177763	9.78822	0	0	0	
+9.428	0.00322203	-0.0257761	9.78022	0	0	0	
+9.429	0.00422203	-0.0337759	9.77222	0	0	0	
+9.43	0.00522202	-0.0417756	9.76422	0	0	0	
+9.431	0.006222	-0.049775	9.75622	0	0	0	
+9.432	0.00722198	-0.0577743	9.74823	0	0	0	
+9.433	0.00822195	-0.0657733	9.74023	0	0	0	
+9.434	0.00922191	-0.0737721	9.73223	0	0	0	
+9.435	0.0102219	-0.0817706	9.72423	0	0	0	
+9.436	0.0112218	-0.0897688	9.71623	0	0	0	
+9.437	0.0122217	-0.0977666	9.70823	0	0	0	
+9.438	0.0132217	-0.105764	9.70024	0	0	0	
+9.439	0.0142216	-0.113761	9.69224	0	0	0	
+9.44	0.0152215	-0.121758	9.68424	0	0	0	
+9.441	0.0162213	-0.129754	9.67625	0	0	0	
+9.442	0.0172212	-0.137749	9.66825	0	0	0	
+9.443	0.018221	-0.145744	9.66026	0	0	0	
+9.444	0.0192209	-0.153738	9.65226	0	0	0	
+9.445	0.0202207	-0.161732	9.64427	0	0	0	
+9.446	0.0212204	-0.169725	9.63627	0	0	0	
+9.447	0.0222202	-0.177718	9.62828	0	0	0	
+9.448	0.02322	-0.18571	9.62029	0	0	0	
+9.449	0.0242197	-0.193701	9.6123	0	0	0	
+9.45	0.0252194	-0.201691	9.60431	0	0	0	
+9.451	0.026219	-0.20968	9.59632	0	0	0	
+9.452	0.0272187	-0.217669	9.58833	0	0	0	
+9.453	0.0282183	-0.225656	9.58034	0	0	0	
+9.454	0.0292179	-0.233643	9.57236	0	0	0	
+9.455	0.0302174	-0.241629	9.56437	0	0	0	
+9.456	0.031217	-0.249614	9.55639	0	0	0	
+9.457	0.0322165	-0.257598	9.5484	0	0	0	
+9.458	0.0332159	-0.265581	9.54042	0	0	0	
+9.459	0.0342154	-0.273563	9.53244	0	0	0	
+9.46	0.0352148	-0.281543	9.52446	0	0	0	
+9.461	0.0362141	-0.289523	9.51648	0	0	0	
+9.462	0.0372134	-0.297501	9.5085	0	0	0	
+9.463	0.0382127	-0.305479	9.50052	0	0	0	
+9.464	0.039212	-0.313455	9.49255	0	0	0	
+9.465	0.0402112	-0.321429	9.48457	0	0	0	
+9.466	0.0412104	-0.329403	9.4766	0	0	0	
+9.467	0.0422095	-0.337375	9.46862	0	0	0	
+9.468	0.0432086	-0.345346	9.46065	0	0	0	
+9.469	0.0442076	-0.353315	9.45268	0	0	0	
+9.47	0.0452066	-0.361283	9.44472	0	0	0	
+9.471	0.0462056	-0.36925	9.43675	0	0	0	
+9.472	0.0472045	-0.377215	9.42879	0	0	0	
+9.473	0.0482034	-0.385179	9.42082	0	0	0	
+9.474	0.0492022	-0.393141	9.41286	0	0	0	
+9.475	0.0502009	-0.401101	9.4049	0	0	0	
+9.476	0.0511996	-0.40906	9.39694	0	0	0	
+9.477	0.0521983	-0.417017	9.38898	0	0	0	
+9.478	0.0531969	-0.424973	9.38103	0	0	0	
+9.479	0.0541955	-0.432927	9.37307	0	0	0	
+9.48	0.055194	-0.440879	9.36512	0	0	0	
+9.481	0.0561924	-0.448829	9.35717	0	0	0	
+9.482	0.0571908	-0.456778	9.34922	0	0	0	
+9.483	0.0581892	-0.464724	9.34128	0	0	0	
+9.484	0.0591874	-0.472669	9.33333	0	0	0	
+9.485	0.0601856	-0.480612	9.32539	0	0	0	
+9.486	0.0611838	-0.488553	9.31745	0	0	0	
+9.487	0.0621819	-0.496493	9.30951	0	0	0	
+9.488	0.0631799	-0.50443	9.30157	0	0	0	
+9.489	0.0641779	-0.512365	9.29364	0	0	0	
+9.49	0.0651758	-0.520298	9.2857	0	0	0	
+9.491	0.0661736	-0.528229	9.27777	0	0	0	
+9.492	0.0671714	-0.536158	9.26984	0	0	0	
+9.493	0.0681691	-0.544084	9.26192	0	0	0	
+9.494	0.0691668	-0.552009	9.25399	0	0	0	
+9.495	0.0701643	-0.559931	9.24607	0	0	0	
+9.496	0.0711618	-0.567851	9.23815	0	0	0	
+9.497	0.0721593	-0.575769	9.23023	0	0	0	
+9.498	0.0731566	-0.583685	9.22232	0	0	0	
+9.499	0.0741539	-0.591598	9.2144	0	0	0	
+9.5	0.0751511	-0.599509	9.20649	0	0	0	
+9.501	0.0761483	-0.607417	9.19858	0	0	0	
+9.502	0.0771453	-0.615323	9.19068	0	0	0	
+9.503	0.0781423	-0.623227	9.18277	0	0	0	
+9.504	0.0791392	-0.631128	9.17487	0	0	0	
+9.505	0.080136	-0.639026	9.16697	0	0	0	
+9.506	0.0811328	-0.646922	9.15908	0	0	0	
+9.507	0.0821294	-0.654816	9.15118	0	0	0	
+9.508	0.083126	-0.662706	9.14329	0	0	0	
+9.509	0.0841225	-0.670595	9.13541	0	0	0	
+9.51	0.0851189	-0.67848	9.12752	0	0	0	
+9.511	0.0861152	-0.686363	9.11964	0	0	0	
+9.512	0.0871115	-0.694243	9.11176	0	0	0	
+9.513	0.0881076	-0.70212	9.10388	0	0	0	
+9.514	0.0891037	-0.709994	9.09601	0	0	0	
+9.515	0.0900997	-0.717866	9.08813	0	0	0	
+9.516	0.0910956	-0.725735	9.08027	0	0	0	
+9.517	0.0920914	-0.7336	9.0724	0	0	0	
+9.518	0.0930871	-0.741463	9.06454	0	0	0	
+9.519	0.0940827	-0.749323	9.05668	0	0	0	
+9.52	0.0950782	-0.75718	9.04882	0	0	0	
+9.521	0.0960736	-0.765034	9.04097	0	0	0	
+9.522	0.097069	-0.772884	9.03312	0	0	0	
+9.523	0.0980642	-0.780732	9.02527	0	0	0	
+9.524	0.0990593	-0.788577	9.01742	0	0	0	
+9.525	0.100054	-0.796418	9.00958	0	0	0	
+9.526	0.101049	-0.804256	9.00174	0	0	0	
+9.527	0.102044	-0.812091	8.99391	0	0	0	
+9.528	0.103039	-0.819923	8.98608	0	0	0	
+9.529	0.104033	-0.827752	8.97825	0	0	0	
+9.53	0.105028	-0.835577	8.97042	0	0	0	
+9.531	0.106022	-0.843399	8.9626	0	0	0	
+9.532	0.107017	-0.851217	8.95478	0	0	0	
+9.533	0.108011	-0.859032	8.94697	0	0	0	
+9.534	0.109005	-0.866844	8.93916	0	0	0	
+9.535	0.109999	-0.874652	8.93135	0	0	0	
+9.536	0.110993	-0.882457	8.92354	0	0	0	
+9.537	0.111987	-0.890258	8.91574	0	0	0	
+9.538	0.11298	-0.898055	8.90794	0	0	0	
+9.539	0.113974	-0.905849	8.90015	0	0	0	
+9.54	0.114967	-0.91364	8.89236	0	0	0	
+9.541	0.115961	-0.921426	8.88457	0	0	0	
+9.542	0.116954	-0.929209	8.87679	0	0	0	
+9.543	0.117947	-0.936989	8.86901	0	0	0	
+9.544	0.11894	-0.944764	8.86124	0	0	0	
+9.545	0.119933	-0.952536	8.85346	0	0	0	
+9.546	0.120925	-0.960304	8.8457	0	0	0	
+9.547	0.121918	-0.968068	8.83793	0	0	0	
+9.548	0.12291	-0.975828	8.83017	0	0	0	
+9.549	0.123903	-0.983584	8.82242	0	0	0	
+9.55	0.124895	-0.991337	8.81466	0	0	0	
+9.551	0.125887	-0.999085	8.80691	0	0	0	
+9.552	0.126879	-1.00683	8.79917	0	0	0	
+9.553	0.127871	-1.01457	8.79143	0	0	0	
+9.554	0.128863	-1.02231	8.78369	0	0	0	
+9.555	0.129854	-1.03004	8.77596	0	0	0	
+9.556	0.130846	-1.03777	8.76823	0	0	0	
+9.557	0.131837	-1.04549	8.76051	0	0	0	
+9.558	0.132828	-1.05321	8.75279	0	0	0	
+9.559	0.133819	-1.06093	8.74507	0	0	0	
+9.56	0.13481	-1.06864	8.73736	0	0	0	
+9.561	0.135801	-1.07634	8.72966	0	0	0	
+9.562	0.136792	-1.08405	8.72195	0	0	0	
+9.563	0.137782	-1.09175	8.71425	0	0	0	
+9.564	0.138773	-1.09944	8.70656	0	0	0	
+9.565	0.139763	-1.10713	8.69887	0	0	0	
+9.566	0.140753	-1.11481	8.69119	0	0	0	
+9.567	0.141743	-1.1225	8.6835	0	0	0	
+9.568	0.142733	-1.13017	8.67583	0	0	0	
+9.569	0.143723	-1.13784	8.66816	0	0	0	
+9.57	0.144712	-1.14551	8.66049	0	0	0	
+9.571	0.145702	-1.15317	8.65283	0	0	0	
+9.572	0.146691	-1.16083	8.64517	0	0	0	
+9.573	0.14768	-1.16848	8.63752	0	0	0	
+9.574	0.148669	-1.17613	8.62987	0	0	0	
+9.575	0.149658	-1.18378	8.62222	0	0	0	
+9.576	0.150646	-1.19142	8.61458	0	0	0	
+9.577	0.151635	-1.19905	8.60695	0	0	0	
+9.578	0.152623	-1.20668	8.59932	0	0	0	
+9.579	0.153611	-1.21431	8.59169	0	0	0	
+9.58	0.154599	-1.22193	8.58407	0	0	0	
+9.581	0.155587	-1.22954	8.57646	0	0	0	
+9.582	0.156575	-1.23715	8.56885	0	0	0	
+9.583	0.157563	-1.24476	8.56124	0	0	0	
+9.584	0.15855	-1.25236	8.55364	0	0	0	
+9.585	0.159537	-1.25995	8.54605	0	0	0	
+9.586	0.160525	-1.26754	8.53846	0	0	0	
+9.587	0.161511	-1.27513	8.53087	0	0	0	
+9.588	0.162498	-1.28271	8.52329	0	0	0	
+9.589	0.163485	-1.29028	8.51572	0	0	0	
+9.59	0.164471	-1.29785	8.50815	0	0	0	
+9.591	0.165458	-1.30542	8.50058	0	0	0	
+9.592	0.166444	-1.31298	8.49302	0	0	0	
+9.593	0.16743	-1.32053	8.48547	0	0	0	
+9.594	0.168416	-1.32808	8.47792	0	0	0	
+9.595	0.169401	-1.33562	8.47038	0	0	0	
+9.596	0.170387	-1.34316	8.46284	0	0	0	
+9.597	0.171372	-1.35069	8.45531	0	0	0	
+9.598	0.172357	-1.35822	8.44778	0	0	0	
+9.599	0.173342	-1.36574	8.44026	0	0	0	
+9.6	0.174327	-1.37326	8.43274	0	0	0	
+9.601	0.175311	-1.38077	8.42523	0	0	0	
+9.602	0.176296	-1.38828	8.41772	0	0	0	
+9.603	0.17728	-1.39578	8.41022	0	0	0	
+9.604	0.178264	-1.40327	8.40273	0	0	0	
+9.605	0.179248	-1.41076	8.39524	0	0	0	
+9.606	0.180232	-1.41824	8.38776	0	0	0	
+9.607	0.181215	-1.42572	8.38028	0	0	0	
+9.608	0.182199	-1.43319	8.37281	0	0	0	
+9.609	0.183182	-1.44066	8.36534	0	0	0	
+9.61	0.184165	-1.44812	8.35788	0	0	0	
+9.611	0.185148	-1.45557	8.35043	0	0	0	
+9.612	0.18613	-1.46302	8.34298	0	0	0	
+9.613	0.187113	-1.47046	8.33554	0	0	0	
+9.614	0.188095	-1.4779	8.3281	0	0	0	
+9.615	0.189077	-1.48533	8.32067	0	0	0	
+9.616	0.190059	-1.49276	8.31324	0	0	0	
+9.617	0.19104	-1.50018	8.30582	0	0	0	
+9.618	0.192022	-1.50759	8.29841	0	0	0	
+9.619	0.193003	-1.515	8.291	0	0	0	
+9.62	0.193984	-1.5224	8.2836	0	0	0	
+9.621	0.194965	-1.52979	8.27621	0	0	0	
+9.622	0.195946	-1.53718	8.26882	0	0	0	
+9.623	0.196926	-1.54456	8.26144	0	0	0	
+9.624	0.197907	-1.55194	8.25406	0	0	0	
+9.625	0.198887	-1.55931	8.24669	0	0	0	
+9.626	0.199867	-1.56667	8.23933	0	0	0	
+9.627	0.200847	-1.57403	8.23197	0	0	0	
+9.628	0.201826	-1.58138	8.22462	0	0	0	
+9.629	0.202805	-1.58873	8.21727	0	0	0	
+9.63	0.203785	-1.59607	8.20993	0	0	0	
+9.631	0.204763	-1.6034	8.2026	0	0	0	
+9.632	0.205742	-1.61072	8.19528	0	0	0	
+9.633	0.206721	-1.61804	8.18796	0	0	0	
+9.634	0.207699	-1.62536	8.18064	0	0	0	
+9.635	0.208677	-1.63266	8.17334	0	0	0	
+9.636	0.209655	-1.63996	8.16604	0	0	0	
+9.637	0.210633	-1.64726	8.15874	0	0	0	
+9.638	0.21161	-1.65454	8.15146	0	0	0	
+9.639	0.212587	-1.66182	8.14418	0	0	0	
+9.64	0.213564	-1.6691	8.1369	0	0	0	
+9.641	0.214541	-1.67636	8.12964	0	0	0	
+9.642	0.215518	-1.68362	8.12238	0	0	0	
+9.643	0.216494	-1.69088	8.11512	0	0	0	
+9.644	0.21747	-1.69812	8.10788	0	0	0	
+9.645	0.218446	-1.70536	8.10064	0	0	0	
+9.646	0.219422	-1.7126	8.0934	0	0	0	
+9.647	0.220398	-1.71982	8.08618	0	0	0	
+9.648	0.221373	-1.72704	8.07896	0	0	0	
+9.649	0.222348	-1.73426	8.07174	0	0	0	
+9.65	0.223323	-1.74146	8.06454	0	0	0	
+9.651	0.224297	-1.74866	8.05734	0	0	0	
+9.652	0.225272	-1.75585	8.05015	0	0	0	
+9.653	0.226246	-1.76304	8.04296	0	0	0	
+9.654	0.22722	-1.77021	8.03579	0	0	0	
+9.655	0.228194	-1.77738	8.02862	0	0	0	
+9.656	0.229167	-1.78455	8.02145	0	0	0	
+9.657	0.23014	-1.7917	8.0143	0	0	0	
+9.658	0.231114	-1.79885	8.00715	0	0	0	
+9.659	0.232086	-1.80599	8.00001	0	0	0	
+9.66	0.233059	-1.81313	7.99287	0	0	0	
+9.661	0.234031	-1.82026	7.98574	0	0	0	
+9.662	0.235003	-1.82738	7.97862	0	0	0	
+9.663	0.235975	-1.83449	7.97151	0	0	0	
+9.664	0.236947	-1.84159	7.96441	0	0	0	
+9.665	0.237918	-1.84869	7.95731	0	0	0	
+9.666	0.238889	-1.85578	7.95022	0	0	0	
+9.667	0.23986	-1.86287	7.94313	0	0	0	
+9.668	0.240831	-1.86994	7.93606	0	0	0	
+9.669	0.241802	-1.87701	7.92899	0	0	0	
+9.67	0.242772	-1.88407	7.92193	0	0	0	
+9.671	0.243742	-1.89112	7.91488	0	0	0	
+9.672	0.244711	-1.89817	7.90783	0	0	0	
+9.673	0.245681	-1.90521	7.90079	0	0	0	
+9.674	0.24665	-1.91224	7.89376	0	0	0	
+9.675	0.247619	-1.91926	7.88674	0	0	0	
+9.676	0.248588	-1.92628	7.87972	0	0	0	
+9.677	0.249556	-1.93328	7.87272	0	0	0	
+9.678	0.250525	-1.94028	7.86572	0	0	0	
+9.679	0.251493	-1.94727	7.85873	0	0	0	
+9.68	0.25246	-1.95426	7.85174	0	0	0	
+9.681	0.253428	-1.96124	7.84476	0	0	0	
+9.682	0.254395	-1.9682	7.8378	0	0	0	
+9.683	0.255362	-1.97516	7.83084	0	0	0	
+9.684	0.256329	-1.98212	7.82388	0	0	0	
+9.685	0.257295	-1.98906	7.81694	0	0	0	
+9.686	0.258261	-1.996	7.81	0	0	0	
+9.687	0.259227	-2.00293	7.80307	0	0	0	
+9.688	0.260193	-2.00985	7.79615	0	0	0	
+9.689	0.261158	-2.01676	7.78924	0	0	0	
+9.69	0.262124	-2.02367	7.78233	0	0	0	
+9.691	0.263088	-2.03056	7.77544	0	0	0	
+9.692	0.264053	-2.03745	7.76855	0	0	0	
+9.693	0.265017	-2.04433	7.76167	0	0	0	
+9.694	0.265982	-2.0512	7.7548	0	0	0	
+9.695	0.266945	-2.05807	7.74793	0	0	0	
+9.696	0.267909	-2.06492	7.74108	0	0	0	
+9.697	0.268872	-2.07177	7.73423	0	0	0	
+9.698	0.269835	-2.07861	7.72739	0	0	0	
+9.699	0.270798	-2.08544	7.72056	0	0	0	
+9.7	0.271761	-2.09226	7.71374	0	0	0	
+9.701	0.272723	-2.09908	7.70692	0	0	0	
+9.702	0.273685	-2.10588	7.70012	0	0	0	
+9.703	0.274646	-2.11268	7.69332	0	0	0	
+9.704	0.275608	-2.11947	7.68653	0	0	0	
+9.705	0.276569	-2.12625	7.67975	0	0	0	
+9.706	0.27753	-2.13302	7.67298	0	0	0	
+9.707	0.27849	-2.13978	7.66622	0	0	0	
+9.708	0.279451	-2.14654	7.65946	0	0	0	
+9.709	0.280411	-2.15329	7.65271	0	0	0	
+9.71	0.281371	-2.16002	7.64598	0	0	0	
+9.711	0.28233	-2.16675	7.63925	0	0	0	
+9.712	0.283289	-2.17347	7.63253	0	0	0	
+9.713	0.284248	-2.18018	7.62582	0	0	0	
+9.714	0.285207	-2.18689	7.61911	0	0	0	
+9.715	0.286165	-2.19358	7.61242	0	0	0	
+9.716	0.287123	-2.20027	7.60573	0	0	0	
+9.717	0.288081	-2.20694	7.59906	0	0	0	
+9.718	0.289038	-2.21361	7.59239	0	0	0	
+9.719	0.289995	-2.22027	7.58573	0	0	0	
+9.72	0.290952	-2.22692	7.57908	0	0	0	
+9.721	0.291909	-2.23356	7.57244	0	0	0	
+9.722	0.292865	-2.24019	7.56581	0	0	0	
+9.723	0.293821	-2.24682	7.55918	0	0	0	
+9.724	0.294777	-2.25343	7.55257	0	0	0	
+9.725	0.295732	-2.26004	7.54596	0	0	0	
+9.726	0.296687	-2.26663	7.53937	0	0	0	
+9.727	0.297642	-2.27322	7.53278	0	0	0	
+9.728	0.298597	-2.2798	7.5262	0	0	0	
+9.729	0.299551	-2.28637	7.51963	0	0	0	
+9.73	0.300505	-2.29293	7.51307	0	0	0	
+9.731	0.301459	-2.29948	7.50652	0	0	0	
+9.732	0.302412	-2.30602	7.49998	0	0	0	
+9.733	0.303365	-2.31255	7.49345	0	0	0	
+9.734	0.304318	-2.31907	7.48693	0	0	0	
+9.735	0.30527	-2.32559	7.48041	0	0	0	
+9.736	0.306222	-2.33209	7.47391	0	0	0	
+9.737	0.307174	-2.33859	7.46741	0	0	0	
+9.738	0.308126	-2.34507	7.46093	0	0	0	
+9.739	0.309077	-2.35155	7.45445	0	0	0	
+9.74	0.310028	-2.35801	7.44799	0	0	0	
+9.741	0.310978	-2.36447	7.44153	0	0	0	
+9.742	0.311928	-2.37092	7.43508	0	0	0	
+9.743	0.312878	-2.37736	7.42864	0	0	0	
+9.744	0.313828	-2.38379	7.42221	0	0	0	
+9.745	0.314777	-2.39021	7.41579	0	0	0	
+9.746	0.315726	-2.39662	7.40938	0	0	0	
+9.747	0.316675	-2.40302	7.40298	0	0	0	
+9.748	0.317623	-2.40941	7.39659	0	0	0	
+9.749	0.318571	-2.41579	7.39021	0	0	0	
+9.75	0.319519	-2.42216	7.38384	0	0	0	
+9.751	0.320467	-2.42852	7.37748	0	0	0	
+9.752	0.321414	-2.43487	7.37113	0	0	0	
+9.753	0.32236	-2.44122	7.36478	0	0	0	
+9.754	0.323307	-2.44755	7.35845	0	0	0	
+9.755	0.324253	-2.45387	7.35213	0	0	0	
+9.756	0.325199	-2.46018	7.34582	0	0	0	
+9.757	0.326144	-2.46649	7.33951	0	0	0	
+9.758	0.32709	-2.47278	7.33322	0	0	0	
+9.759	0.328034	-2.47906	7.32694	0	0	0	
+9.76	0.328979	-2.48534	7.32066	0	0	0	
+9.761	0.329923	-2.4916	7.3144	0	0	0	
+9.762	0.330867	-2.49785	7.30815	0	0	0	
+9.763	0.33181	-2.5041	7.3019	0	0	0	
+9.764	0.332754	-2.51033	7.29567	0	0	0	
+9.765	0.333696	-2.51655	7.28945	0	0	0	
+9.766	0.334639	-2.52277	7.28323	0	0	0	
+9.767	0.335581	-2.52897	7.27703	0	0	0	
+9.768	0.336523	-2.53516	7.27084	0	0	0	
+9.769	0.337464	-2.54135	7.26465	0	0	0	
+9.77	0.338406	-2.54752	7.25848	0	0	0	
+9.771	0.339346	-2.55368	7.25232	0	0	0	
+9.772	0.340287	-2.55983	7.24617	0	0	0	
+9.773	0.341227	-2.56598	7.24002	0	0	0	
+9.774	0.342167	-2.57211	7.23389	0	0	0	
+9.775	0.343106	-2.57823	7.22777	0	0	0	
+9.776	0.344046	-2.58434	7.22166	0	0	0	
+9.777	0.344984	-2.59044	7.21556	0	0	0	
+9.778	0.345923	-2.59653	7.20947	0	0	0	
+9.779	0.346861	-2.60261	7.20339	0	0	0	
+9.78	0.347799	-2.60868	7.19732	0	0	0	
+9.781	0.348736	-2.61474	7.19126	0	0	0	
+9.782	0.349673	-2.62079	7.18521	0	0	0	
+9.783	0.35061	-2.62683	7.17917	0	0	0	
+9.784	0.351546	-2.63286	7.17314	0	0	0	
+9.785	0.352482	-2.63887	7.16713	0	0	0	
+9.786	0.353418	-2.64488	7.16112	0	0	0	
+9.787	0.354353	-2.65088	7.15512	0	0	0	
+9.788	0.355288	-2.65686	7.14914	0	0	0	
+9.789	0.356222	-2.66284	7.14316	0	0	0	
+9.79	0.357157	-2.6688	7.1372	0	0	0	
+9.791	0.358091	-2.67476	7.13124	0	0	0	
+9.792	0.359024	-2.6807	7.1253	0	0	0	
+9.793	0.359957	-2.68663	7.11937	0	0	0	
+9.794	0.36089	-2.69255	7.11345	0	0	0	
+9.795	0.361822	-2.69846	7.10754	0	0	0	
+9.796	0.362755	-2.70436	7.10164	0	0	0	
+9.797	0.363686	-2.71025	7.09575	0	0	0	
+9.798	0.364618	-2.71613	7.08987	0	0	0	
+9.799	0.365549	-2.722	7.084	0	0	0	
+9.8	0.366479	-2.72785	7.07815	0	0	0	
+9.801	0.367409	-2.7337	7.0723	0	0	0	
+9.802	0.368339	-2.73953	7.06647	0	0	0	
+9.803	0.369269	-2.74536	7.06064	0	0	0	
+9.804	0.370198	-2.75117	7.05483	0	0	0	
+9.805	0.371127	-2.75697	7.04903	0	0	0	
+9.806	0.372055	-2.76276	7.04324	0	0	0	
+9.807	0.372983	-2.76854	7.03746	0	0	0	
+9.808	0.373911	-2.77431	7.03169	0	0	0	
+9.809	0.374838	-2.78007	7.02593	0	0	0	
+9.81	0.375765	-2.78582	7.02018	0	0	0	
+9.811	0.376691	-2.79155	7.01445	0	0	0	
+9.812	0.377618	-2.79728	7.00872	0	0	0	
+9.813	0.378543	-2.80299	7.00301	0	0	0	
+9.814	0.379469	-2.80869	6.99731	0	0	0	
+9.815	0.380394	-2.81438	6.99162	0	0	0	
+9.816	0.381318	-2.82006	6.98594	0	0	0	
+9.817	0.382243	-2.82573	6.98027	0	0	0	
+9.818	0.383167	-2.83138	6.97462	0	0	0	
+9.819	0.38409	-2.83703	6.96897	0	0	0	
+9.82	0.385013	-2.84266	6.96334	0	0	0	
+9.821	0.385936	-2.84829	6.95771	0	0	0	
+9.822	0.386858	-2.8539	6.9521	0	0	0	
+9.823	0.38778	-2.8595	6.9465	0	0	0	
+9.824	0.388702	-2.86508	6.94092	0	0	0	
+9.825	0.389623	-2.87066	6.93534	0	0	0	
+9.826	0.390544	-2.87623	6.92977	0	0	0	
+9.827	0.391464	-2.88178	6.92422	0	0	0	
+9.828	0.392384	-2.88732	6.91868	0	0	0	
+9.829	0.393304	-2.89285	6.91315	0	0	0	
+9.83	0.394223	-2.89837	6.90763	0	0	0	
+9.831	0.395142	-2.90388	6.90212	0	0	0	
+9.832	0.39606	-2.90938	6.89662	0	0	0	
+9.833	0.396978	-2.91486	6.89114	0	0	0	
+9.834	0.397896	-2.92033	6.88567	0	0	0	
+9.835	0.398813	-2.92579	6.88021	0	0	0	
+9.836	0.39973	-2.93124	6.87476	0	0	0	
+9.837	0.400646	-2.93668	6.86932	0	0	0	
+9.838	0.401562	-2.94211	6.86389	0	0	0	
+9.839	0.402478	-2.94752	6.85848	0	0	0	
+9.84	0.403393	-2.95292	6.85308	0	0	0	
+9.841	0.404308	-2.95831	6.84769	0	0	0	
+9.842	0.405222	-2.96369	6.84231	0	0	0	
+9.843	0.406136	-2.96906	6.83694	0	0	0	
+9.844	0.40705	-2.97441	6.83159	0	0	0	
+9.845	0.407963	-2.97976	6.82624	0	0	0	
+9.846	0.408876	-2.98509	6.82091	0	0	0	
+9.847	0.409788	-2.99041	6.81559	0	0	0	
+9.848	0.4107	-2.99572	6.81028	0	0	0	
+9.849	0.411612	-3.00101	6.80499	0	0	0	
+9.85	0.412523	-3.00629	6.79971	0	0	0	
+9.851	0.413434	-3.01156	6.79444	0	0	0	
+9.852	0.414344	-3.01682	6.78918	0	0	0	
+9.853	0.415254	-3.02207	6.78393	0	0	0	
+9.854	0.416164	-3.02731	6.77869	0	0	0	
+9.855	0.417073	-3.03253	6.77347	0	0	0	
+9.856	0.417981	-3.03774	6.76826	0	0	0	
+9.857	0.41889	-3.04294	6.76306	0	0	0	
+9.858	0.419797	-3.04812	6.75788	0	0	0	
+9.859	0.420705	-3.0533	6.7527	0	0	0	
+9.86	0.421612	-3.05846	6.74754	0	0	0	
+9.861	0.422518	-3.06361	6.74239	0	0	0	
+9.862	0.423424	-3.06875	6.73725	0	0	0	
+9.863	0.42433	-3.07387	6.73213	0	0	0	
+9.864	0.425235	-3.07899	6.72701	0	0	0	
+9.865	0.42614	-3.08409	6.72191	0	0	0	
+9.866	0.427045	-3.08918	6.71682	0	0	0	
+9.867	0.427949	-3.09425	6.71175	0	0	0	
+9.868	0.428852	-3.09931	6.70669	0	0	0	
+9.869	0.429756	-3.10437	6.70163	0	0	0	
+9.87	0.430658	-3.1094	6.6966	0	0	0	
+9.871	0.431561	-3.11443	6.69157	0	0	0	
+9.872	0.432462	-3.11944	6.68656	0	0	0	
+9.873	0.433364	-3.12445	6.68155	0	0	0	
+9.874	0.434265	-3.12944	6.67656	0	0	0	
+9.875	0.435165	-3.13441	6.67159	0	0	0	
+9.876	0.436066	-3.13938	6.66662	0	0	0	
+9.877	0.436965	-3.14433	6.66167	0	0	0	
+9.878	0.437865	-3.14927	6.65673	0	0	0	
+9.879	0.438763	-3.15419	6.65181	0	0	0	
+9.88	0.439662	-3.1591	6.6469	0	0	0	
+9.881	0.44056	-3.16401	6.64199	0	0	0	
+9.882	0.441457	-3.16889	6.63711	0	0	0	
+9.883	0.442354	-3.17377	6.63223	0	0	0	
+9.884	0.443251	-3.17863	6.62737	0	0	0	
+9.885	0.444147	-3.18348	6.62252	0	0	0	
+9.886	0.445043	-3.18832	6.61768	0	0	0	
+9.887	0.445938	-3.19314	6.61286	0	0	0	
+9.888	0.446833	-3.19796	6.60804	0	0	0	
+9.889	0.447727	-3.20276	6.60324	0	0	0	
+9.89	0.448621	-3.20754	6.59846	0	0	0	
+9.891	0.449515	-3.21231	6.59369	0	0	0	
+9.892	0.450408	-3.21708	6.58892	0	0	0	
+9.893	0.4513	-3.22182	6.58418	0	0	0	
+9.894	0.452193	-3.22656	6.57944	0	0	0	
+9.895	0.453084	-3.23128	6.57472	0	0	0	
+9.896	0.453975	-3.23599	6.57001	0	0	0	
+9.897	0.454866	-3.24068	6.56532	0	0	0	
+9.898	0.455757	-3.24537	6.56063	0	0	0	
+9.899	0.456646	-3.25004	6.55596	0	0	0	
+9.9	0.457536	-3.25469	6.55131	0	0	0	
+9.901	0.458425	-3.25934	6.54666	0	0	0	
+9.902	0.459313	-3.26397	6.54203	0	0	0	
+9.903	0.460201	-3.26859	6.53741	0	0	0	
+9.904	0.461089	-3.27319	6.53281	0	0	0	
+9.905	0.461976	-3.27778	6.52822	0	0	0	
+9.906	0.462863	-3.28236	6.52364	0	0	0	
+9.907	0.463749	-3.28693	6.51907	0	0	0	
+9.908	0.464635	-3.29148	6.51452	0	0	0	
+9.909	0.46552	-3.29602	6.50998	0	0	0	
+9.91	0.466405	-3.30055	6.50545	0	0	0	
+9.911	0.467289	-3.30506	6.50094	0	0	0	
+9.912	0.468173	-3.30956	6.49644	0	0	0	
+9.913	0.469056	-3.31405	6.49195	0	0	0	
+9.914	0.469939	-3.31852	6.48748	0	0	0	
+9.915	0.470822	-3.32298	6.48302	0	0	0	
+9.916	0.471704	-3.32743	6.47857	0	0	0	
+9.917	0.472585	-3.33186	6.47414	0	0	0	
+9.918	0.473466	-3.33628	6.46972	0	0	0	
+9.919	0.474347	-3.34068	6.46532	0	0	0	
+9.92	0.475227	-3.34508	6.46092	0	0	0	
+9.921	0.476107	-3.34946	6.45654	0	0	0	
+9.922	0.476986	-3.35382	6.45218	0	0	0	
+9.923	0.477864	-3.35818	6.44782	0	0	0	
+9.924	0.478743	-3.36252	6.44348	0	0	0	
+9.925	0.47962	-3.36684	6.43916	0	0	0	
+9.926	0.480498	-3.37116	6.43484	0	0	0	
+9.927	0.481374	-3.37546	6.43054	0	0	0	
+9.928	0.482251	-3.37974	6.42626	0	0	0	
+9.929	0.483126	-3.38401	6.42199	0	0	0	
+9.93	0.484002	-3.38827	6.41773	0	0	0	
+9.931	0.484877	-3.39252	6.41348	0	0	0	
+9.932	0.485751	-3.39675	6.40925	0	0	0	
+9.933	0.486625	-3.40097	6.40503	0	0	0	
+9.934	0.487498	-3.40517	6.40083	0	0	0	
+9.935	0.488371	-3.40936	6.39664	0	0	0	
+9.936	0.489243	-3.41354	6.39246	0	0	0	
+9.937	0.490115	-3.4177	6.3883	0	0	0	
+9.938	0.490987	-3.42185	6.38415	0	0	0	
+9.939	0.491858	-3.42599	6.38001	0	0	0	
+9.94	0.492728	-3.43011	6.37589	0	0	0	
+9.941	0.493598	-3.43422	6.37178	0	0	0	
+9.942	0.494467	-3.43831	6.36769	0	0	0	
+9.943	0.495336	-3.44239	6.36361	0	0	0	
+9.944	0.496205	-3.44646	6.35954	0	0	0	
+9.945	0.497073	-3.45052	6.35548	0	0	0	
+9.946	0.49794	-3.45456	6.35144	0	0	0	
+9.947	0.498807	-3.45858	6.34742	0	0	0	
+9.948	0.499674	-3.46259	6.34341	0	0	0	
+9.949	0.50054	-3.46659	6.33941	0	0	0	
+9.95	0.501405	-3.47058	6.33542	0	0	0	
+9.951	0.50227	-3.47455	6.33145	0	0	0	
+9.952	0.503135	-3.4785	6.3275	0	0	0	
+9.953	0.503999	-3.48245	6.32355	0	0	0	
+9.954	0.504862	-3.48638	6.31962	0	0	0	
+9.955	0.505725	-3.49029	6.31571	0	0	0	
+9.956	0.506587	-3.49419	6.31181	0	0	0	
+9.957	0.507449	-3.49808	6.30792	0	0	0	
+9.958	0.508311	-3.50195	6.30405	0	0	0	
+9.959	0.509172	-3.50581	6.30019	0	0	0	
+9.96	0.510032	-3.50965	6.29635	0	0	0	
+9.961	0.510892	-3.51349	6.29251	0	0	0	
+9.962	0.511751	-3.5173	6.2887	0	0	0	
+9.963	0.51261	-3.5211	6.2849	0	0	0	
+9.964	0.513469	-3.52489	6.28111	0	0	0	
+9.965	0.514326	-3.52867	6.27733	0	0	0	
+9.966	0.515184	-3.53243	6.27357	0	0	0	
+9.967	0.516041	-3.53617	6.26983	0	0	0	
+9.968	0.516897	-3.53991	6.26609	0	0	0	
+9.969	0.517753	-3.54363	6.26237	0	0	0	
+9.97	0.518608	-3.54733	6.25867	0	0	0	
+9.971	0.519463	-3.55102	6.25498	0	0	0	
+9.972	0.520317	-3.55469	6.25131	0	0	0	
+9.973	0.521171	-3.55836	6.24764	0	0	0	
+9.974	0.522024	-3.562	6.244	0	0	0	
+9.975	0.522877	-3.56563	6.24037	0	0	0	
+9.976	0.523729	-3.56925	6.23675	0	0	0	
+9.977	0.52458	-3.57286	6.23314	0	0	0	
+9.978	0.525431	-3.57645	6.22955	0	0	0	
+9.979	0.526282	-3.58002	6.22598	0	0	0	
+9.98	0.527132	-3.58358	6.22242	0	0	0	
+9.981	0.527982	-3.58713	6.21887	0	0	0	
+9.982	0.528831	-3.59066	6.21534	0	0	0	
+9.983	0.529679	-3.59418	6.21182	0	0	0	
+9.984	0.530527	-3.59769	6.20831	0	0	0	
+9.985	0.531374	-3.60118	6.20482	0	0	0	
+9.986	0.532221	-3.60465	6.20135	0	0	0	
+9.987	0.533068	-3.60811	6.19789	0	0	0	
+9.988	0.533913	-3.61156	6.19444	0	0	0	
+9.989	0.534759	-3.61499	6.19101	0	0	0	
+9.99	0.535603	-3.61841	6.18759	0	0	0	
+9.991	0.536448	-3.62181	6.18419	0	0	0	
+9.992	0.537291	-3.6252	6.1808	0	0	0	
+9.993	0.538134	-3.62857	6.17743	0	0	0	
+9.994	0.538977	-3.63193	6.17407	0	0	0	
+9.995	0.539819	-3.63528	6.17072	0	0	0	
+9.996	0.54066	-3.63861	6.16739	0	0	0	
+9.997	0.541501	-3.64192	6.16408	0	0	0	
+9.998	0.542342	-3.64522	6.16078	0	0	0	
+9.999	0.543182	-3.64851	6.15749	0	0	0	
+10	0.544021	-3.65178	6.15422	0	0	0	
diff --git a/src/test/data/IMU/data_trajectory_full.txt b/src/test/data/IMU/data_trajectory_full.txt
new file mode 100644
index 0000000000000000000000000000000000000000..d7ee32db2c4cfb3d6f5266873055cbfce6b2c4a6
--- /dev/null
+++ b/src/test/data/IMU/data_trajectory_full.txt
@@ -0,0 +1,1002 @@
+0.0000000000000000	0.0000000000000000	0.0000000000000000	1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	1.0000000000000000	2.0000000000000000	2.0000000000000000	
+0.0000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.2741556778080377	0.1096622711232151	0.2741556778080377	
+0.0010000000000000	-0.0009999998333333	-0.0079999946666677	9.7920000053333336	0.2741556767641303	0.1096622710564050	0.2741556767641303	
+0.0020000000000000	-0.0030769532454230	-0.0133169216936024	9.7840037829860513	0.2741556736324080	0.1096622708559748	0.2741556736324080	
+0.0030000000000000	-0.0051558027789035	-0.0186373249517765	9.7760109388420950	0.2741556684128708	0.1096622705219244	0.2741556684128708	
+0.0040000000000000	-0.0072365494729966	-0.0239611700236307	9.7680215059662459	0.2741556611055188	0.1096622700542539	0.2741556611055188	
+0.0050000000000000	-0.0093191943450105	-0.0292884224568465	9.7600355173869371	0.2741556517103521	0.1096622694529632	0.2741556517103521	
+0.0060000000000000	-0.0114037383903079	-0.0346190477645144	9.7520530060961210	0.2741556402273708	0.1096622687180524	0.2741556402273708	
+0.0070000000000000	-0.0134901825822743	-0.0399530114253015	9.7440740050491055	0.2741556266565747	0.1096622678495214	0.2741556266565747	
+0.0080000000000000	-0.0155785278722862	-0.0452902788836199	9.7360985471644419	0.2741556109979643	0.1096622668473703	0.2741556109979643	
+0.0090000000000000	-0.0176687751896796	-0.0506308155497952	9.7281266653237530	0.2741555932515394	0.1096622657115990	0.2741555932515394	
+0.0100000000000000	-0.0197609254417187	-0.0559745868002349	9.7201583923716015	0.2741555734173003	0.1096622644422075	0.2741555734173003	
+0.0110000000000000	-0.0218549795135643	-0.0613215579775979	9.7121937611153406	0.2741555514952472	0.1096622630391960	0.2741555514952472	
+0.0120000000000000	-0.0239509382682430	-0.0666716943909632	9.7042328043249739	0.2741555274853801	0.1096622615025643	0.2741555274853801	
+0.0130000000000000	-0.0260488025466162	-0.0720249613159994	9.6962755547330080	0.2741555013876993	0.1096622598323124	0.2741555013876993	
+0.0140000000000000	-0.0281485731673492	-0.0773813239951343	9.6883220450343153	0.2741554732022050	0.1096622580284404	0.2741554732022050	
+0.0150000000000000	-0.0302502509268806	-0.0827407476377249	9.6803723078859854	0.2741554429288973	0.1096622560909483	0.2741554429288973	
+0.0160000000000000	-0.0323538365993917	-0.0881031974202274	9.6724263759071896	0.2741554105677765	0.1096622540198361	0.2741554105677765	
+0.0170000000000000	-0.0344593309367761	-0.0934686384863672	9.6644842816790213	0.2741553761188429	0.1096622518151037	0.2741553761188429	
+0.0180000000000000	-0.0365667346686098	-0.0988370359473101	9.6565460577443840	0.2741553395820968	0.1096622494767511	0.2741553395820968	
+0.0190000000000000	-0.0386760485021208	-0.1042083548818323	9.6486117366078172	0.2741553009575383	0.1096622470047785	0.2741553009575383	
+0.0200000000000000	-0.0407872731221591	-0.1095825603364920	9.6406813507353739	0.2741552602451677	0.1096622443991857	0.2741552602451677	
+0.0210000000000000	-0.0429004091911673	-0.1149596173258000	9.6327549325544801	0.2741552174449856	0.1096622416599728	0.2741552174449856	
+0.0220000000000000	-0.0450154573491508	-0.1203394908323917	9.6248325144537770	0.2741551725569920	0.1096622387871398	0.2741551725569920	
+0.0230000000000000	-0.0471324182136484	-0.1257221458071984	9.6169141287829962	0.2741551255811874	0.1096622357806867	0.2741551255811874	
+0.0240000000000000	-0.0492512923797026	-0.1311075471696192	9.6089998078528183	0.2741550765175721	0.1096622326406135	0.2741550765175721	
+0.0250000000000000	-0.0513720804198310	-0.1364956598076931	9.6010895839347281	0.2741550253661466	0.1096622293669201	0.2741550253661466	
+0.0260000000000000	-0.0534947828839970	-0.1418864485782714	9.5931834892608663	0.2741549721269110	0.1096622259596067	0.2741549721269110	
+0.0270000000000000	-0.0556194002995809	-0.1472798783071899	9.5852815560239026	0.2741549167998661	0.1096622224186732	0.2741549167998661	
+0.0280000000000000	-0.0577459331713512	-0.1526759137894421	9.5773838163768854	0.2741548593850121	0.1096622187441196	0.2741548593850121	
+0.0290000000000000	-0.0598743819814364	-0.1580745197893519	9.5694903024331239	0.2741547998823493	0.1096622149359458	0.2741547998823493	
+0.0300000000000000	-0.0620047471892960	-0.1634756610407464	9.5616010462660217	0.2741547382918784	0.1096622109941521	0.2741547382918784	
+0.0310000000000000	-0.0641370292316925	-0.1688793022471302	9.5537160799089467	0.2741546746135998	0.1096622069187382	0.2741546746135998	
+0.0320000000000000	-0.0662712285226637	-0.1742854080818578	9.5458354353551034	0.2741546088475139	0.1096622027097042	0.2741546088475139	
+0.0330000000000000	-0.0684073454534941	-0.1796939431883086	9.5379591445573890	0.2741545409936213	0.1096621983670502	0.2741545409936213	
+0.0340000000000000	-0.0705453803926875	-0.1851048721800598	9.5300872394282408	0.2741544710519225	0.1096621938907761	0.2741544710519225	
+0.0350000000000000	-0.0726853336859392	-0.1905181596410616	9.5222197518395184	0.2741543990224179	0.1096621892808820	0.2741543990224179	
+0.0360000000000000	-0.0748272056561088	-0.1959337701258106	9.5143567136223570	0.2741543249051083	0.1096621845373678	0.2741543249051083	
+0.0370000000000000	-0.0769709966031925	-0.2013516681595257	9.5064981565670372	0.2741542486999941	0.1096621796602335	0.2741542486999941	
+0.0380000000000000	-0.0791167068042960	-0.2067718182383219	9.4986441124228360	0.2741541704070758	0.1096621746494793	0.2741541704070758	
+0.0390000000000000	-0.0812643365136079	-0.2121941848293857	9.4907946128978988	0.2741540900263542	0.1096621695051049	0.2741540900263542	
+0.0400000000000000	-0.0834138859623722	-0.2176187323711503	9.4829496896590939	0.2741540075578298	0.1096621642271106	0.2741540075578298	
+0.0410000000000000	-0.0855653553588619	-0.2230454252734712	9.4751093743318844	0.2741539230015032	0.1096621588154962	0.2741539230015032	
+0.0420000000000000	-0.0877187448883527	-0.2284742279178019	9.4672736985002022	0.2741538363573752	0.1096621532702619	0.2741538363573752	
+0.0430000000000000	-0.0898740547130962	-0.2339051046573693	9.4594426937062916	0.2741537476254462	0.1096621475914075	0.2741537476254462	
+0.0440000000000000	-0.0920312849722937	-0.2393380198173505	9.4516163914505746	0.2741536568057171	0.1096621417789331	0.2741536568057171	
+0.0450000000000000	-0.0941904357820706	-0.2447729376950485	9.4437948231915421	0.2741535638981885	0.1096621358328387	0.2741535638981885	
+0.0460000000000000	-0.0963515072354496	-0.2502098225600690	9.4359780203455870	0.2741534689028611	0.1096621297531243	0.2741534689028611	
+0.0470000000000000	-0.0985144994023260	-0.2556486386544969	9.4281660142868962	0.2741533718197356	0.1096621235397900	0.2741533718197356	
+0.0480000000000000	-0.1006794123294411	-0.2610893501930729	9.4203588363472868	0.2741532726488129	0.1096621171928356	0.2741532726488129	
+0.0490000000000000	-0.1028462460403574	-0.2665319213633712	9.4125565178160997	0.2741531713900935	0.1096621107122614	0.2741531713900935	
+0.0500000000000000	-0.1050150005354330	-0.2719763163259764	9.4047590899400557	0.2741530680435785	0.1096621040980671	0.2741530680435785	
+0.0510000000000000	-0.1071856757917966	-0.2774224992146608	9.3969665839231151	0.2741529626092683	0.1096620973502529	0.2741529626092683	
+0.0520000000000000	-0.1093582717633224	-0.2828704341365622	9.3891790309263516	0.2741528550871640	0.1096620904688188	0.2741528550871640	
+0.0530000000000000	-0.1115327883806056	-0.2883200851723621	9.3813964620678245	0.2741527454772663	0.1096620834537647	0.2741527454772663	
+0.0540000000000000	-0.1137092255509371	-0.2937714163764630	9.3736189084224328	0.2741526337795760	0.1096620763050907	0.2741526337795760	
+0.0550000000000000	-0.1158875831582797	-0.2992243917771675	9.3658464010217912	0.2741525199940941	0.1096620690227968	0.2741525199940941	
+0.0560000000000000	-0.1180678610632434	-0.3046789753768557	9.3580789708540948	0.2741524041208213	0.1096620616068830	0.2741524041208213	
+0.0570000000000000	-0.1202500591030612	-0.3101351311521650	9.3503166488639877	0.2741522861597586	0.1096620540573493	0.2741522861597586	
+0.0580000000000000	-0.1224341770915652	-0.3155928230541675	9.3425594659524354	0.2741521661109068	0.1096620463741957	0.2741521661109068	
+0.0590000000000000	-0.1246202148191626	-0.3210520150085506	9.3348074529765892	0.2741520439742669	0.1096620385574222	0.2741520439742669	
+0.0600000000000000	-0.1268081720528123	-0.3265126709157945	9.3270606407496590	0.2741519197498398	0.1096620306070289	0.2741519197498398	
+0.0610000000000000	-0.1289980485360011	-0.3319747546513531	9.3193190600407743	0.2741517934376264	0.1096620225230156	0.2741517934376264	
+0.0620000000000000	-0.1311898439887202	-0.3374382300658325	9.3115827415748580	0.2741516650376277	0.1096620143053826	0.2741516650376277	
+0.0630000000000000	-0.1333835581074423	-0.3429030609851709	9.3038517160325025	0.2741515345498447	0.1096620059541297	0.2741515345498447	
+0.0640000000000000	-0.1355791905650984	-0.3483692112108190	9.2961260140498343	0.2741514019742785	0.1096619974692570	0.2741514019742785	
+0.0650000000000000	-0.1377767410110549	-0.3538366445199194	9.2884056662183774	0.2741512673109298	0.1096619888507644	0.2741512673109298	
+0.0660000000000000	-0.1399762090710908	-0.3593053246654875	9.2806907030849377	0.2741511305597998	0.1096619800986521	0.2741511305597998	
+0.0670000000000000	-0.1421775943473755	-0.3647752153765920	9.2729811551514594	0.2741509917208897	0.1096619712129199	0.2741509917208897	
+0.0680000000000000	-0.1443808964184457	-0.3702462803585344	9.2652770528749144	0.2741508507942003	0.1096619621935680	0.2741508507942003	
+0.0690000000000000	-0.1465861148391838	-0.3757184832930310	9.2575784266671484	0.2741507077797329	0.1096619530405963	0.2741507077797329	
+0.0700000000000000	-0.1487932491407956	-0.3811917878383944	9.2498853068947859	0.2741505626774883	0.1096619437540048	0.2741505626774883	
+0.0710000000000000	-0.1510022988307882	-0.3866661576297122	9.2421977238790625	0.2741504154874679	0.1096619343337936	0.2741504154874679	
+0.0720000000000000	-0.1532132633929486	-0.3921415562790314	9.2345157078957385	0.2741502662096726	0.1096619247799626	0.2741502662096726	
+0.0730000000000000	-0.1554261422873217	-0.3976179473755371	9.2268392891749276	0.2741501148441037	0.1096619150925119	0.2741501148441037	
+0.0740000000000000	-0.1576409349501894	-0.4030952944857372	9.2191684979010180	0.2741499613907623	0.1096619052714415	0.2741499613907623	
+0.0750000000000000	-0.1598576407940487	-0.4085735611536412	9.2115033642125024	0.2741498058496496	0.1096618953167514	0.2741498058496496	
+0.0760000000000000	-0.1620762592075911	-0.4140527109009442	9.2038439182018781	0.2741496482207666	0.1096618852284415	0.2741496482207666	
+0.0770000000000000	-0.1642967895556815	-0.4195327072272090	9.1961901899155105	0.2741494885041147	0.1096618750065120	0.2741494885041147	
+0.0780000000000000	-0.1665192311793375	-0.4250135136100475	9.1885422093535052	0.2741493266996951	0.1096618646509629	0.2741493266996951	
+0.0790000000000000	-0.1687435833957085	-0.4304950935053035	9.1809000064695905	0.2741491628075089	0.1096618541617940	0.2741491628075089	
+0.0800000000000000	-0.1709698454980556	-0.4359774103472364	9.1732636111709844	0.2741489968275575	0.1096618435390056	0.2741489968275575	
+0.0810000000000000	-0.1731980167557312	-0.4414604275487031	9.1656330533182739	0.2741488287598421	0.1096618327825975	0.2741488287598421	
+0.0820000000000000	-0.1754280964141592	-0.4469441085013414	9.1580083627252868	0.2741486586043640	0.1096618218925697	0.2741486586043640	
+0.0830000000000000	-0.1776600836948142	-0.4524284165757532	9.1503895691589712	0.2741484863611244	0.1096618108689224	0.2741484863611244	
+0.0840000000000000	-0.1798939777952027	-0.4579133151216875	9.1427767023392654	0.2741483120301247	0.1096617997116555	0.2741483120301247	
+0.0850000000000000	-0.1821297778888430	-0.4633987674682247	9.1351697919389796	0.2741481356113663	0.1096617884207690	0.2741481356113663	
+0.0860000000000000	-0.1843674831252458	-0.4688847369239597	9.1275688675836690	0.2741479571048505	0.1096617769962629	0.2741479571048505	
+0.0870000000000000	-0.1866070926298950	-0.4743711867771860	9.1199739588515101	0.2741477765105784	0.1096617654381373	0.2741477765105784	
+0.0880000000000000	-0.1888486055042286	-0.4798580802960795	9.1123850952731846	0.2741475938285517	0.1096617537463922	0.2741475938285517	
+0.0890000000000000	-0.1910920208256196	-0.4853453807288830	9.1048023063317380	0.2741474090587717	0.1096617419210275	0.2741474090587717	
+0.0900000000000000	-0.1933373376473574	-0.4908330513040904	9.0972256214624849	0.2741472222012398	0.1096617299620433	0.2741472222012398	
+0.0910000000000000	-0.1955845549986292	-0.4963210552306312	9.0896550700528564	0.2741470332559575	0.1096617178694396	0.2741470332559575	
+0.0920000000000000	-0.1978336718845015	-0.5018093556980554	9.0820906814423079	0.2741468422229260	0.1096617056432165	0.2741468422229260	
+0.0930000000000000	-0.2000846872859017	-0.5072979158767172	9.0745324849221696	0.2741466491021470	0.1096616932833739	0.2741466491021470	
+0.0940000000000000	-0.2023376001596003	-0.5127866989179617	9.0669805097355489	0.2741464538936219	0.1096616807899118	0.2741464538936219	
+0.0950000000000000	-0.2045924094381926	-0.5182756679543090	9.0594347850771904	0.2741462565973520	0.1096616681628303	0.2741462565973520	
+0.0960000000000000	-0.2068491140300815	-0.5237647860996394	9.0518953400933668	0.2741460572133391	0.1096616554021294	0.2741460572133391	
+0.0970000000000000	-0.2091077128194589	-0.5292540164493789	9.0443622038817484	0.2741458557415846	0.1096616425078091	0.2741458557415846	
+0.0980000000000000	-0.2113682046662897	-0.5347433220806854	9.0368354054913063	0.2741456521820900	0.1096616294798694	0.2741456521820900	
+0.0990000000000000	-0.2136305884062933	-0.5402326660526340	9.0293149739221565	0.2741454465348568	0.1096616163183103	0.2741454465348568	
+0.1000000000000000	-0.2158948628509271	-0.5457220114064023	9.0218009381254767	0.2741452387998868	0.1096616030231319	0.2741452387998868	
+0.1010000000000000	-0.2181610267873694	-0.5512113211654572	9.0142933270033581	0.2741450289771812	0.1096615895943342	0.2741450289771812	
+0.1020000000000000	-0.2204290789785028	-0.5567005583357412	9.0067921694086976	0.2741448170667420	0.1096615760319171	0.2741448170667420	
+0.1030000000000000	-0.2226990181628973	-0.5621896859058569	8.9992974941450825	0.2741446030685706	0.1096615623358807	0.2741446030685706	
+0.1040000000000000	-0.2249708430547944	-0.5676786668472569	8.9918093299666673	0.2741443869826686	0.1096615485062250	0.2741443869826686	
+0.1050000000000000	-0.2272445523440906	-0.5731674641144269	8.9843277055780639	0.2741441688090377	0.1096615345429501	0.2741441688090377	
+0.1060000000000000	-0.2295201446963213	-0.5786560406450753	8.9768526496342140	0.2741439485476797	0.1096615204460559	0.2741439485476797	
+0.1070000000000000	-0.2317976187526448	-0.5841443593603169	8.9693841907402696	0.2741437261985959	0.1096615062155424	0.2741437261985959	
+0.1080000000000000	-0.2340769731298269	-0.5896323831648634	8.9619223574514866	0.2741435017617884	0.1096614918514097	0.2741435017617884	
+0.1090000000000000	-0.2363582064202250	-0.5951200749472079	8.9544671782731022	0.2741432752372588	0.1096614773536579	0.2741432752372588	
+0.1100000000000000	-0.2386413171917731	-0.6006073975798137	8.9470186816602091	0.2741430466250087	0.1096614627222868	0.2741430466250087	
+0.1110000000000000	-0.2409263039879660	-0.6060943139193011	8.9395768960176660	0.2741428159250399	0.1096614479572966	0.2741428159250399	
+0.1120000000000000	-0.2432131653278453	-0.6115807868066350	8.9321418496999510	0.2741425831373542	0.1096614330586873	0.2741425831373542	
+0.1130000000000000	-0.2455018997059834	-0.6170667790673137	8.9247135710110648	0.2741423482619533	0.1096614180264587	0.2741423482619533	
+0.1140000000000000	-0.2477925055924692	-0.6225522535115542	8.9172920882044071	0.2741421112988390	0.1096614028606111	0.2741421112988390	
+0.1150000000000000	-0.2500849814328941	-0.6280371729344831	8.9098774294826626	0.2741418722480133	0.1096613875611444	0.2741418722480133	
+0.1160000000000000	-0.2523793256483369	-0.6335215001163232	8.9024696229976907	0.2741416311094777	0.1096613721280587	0.2741416311094777	
+0.1170000000000000	-0.2546755366353503	-0.6390051978225809	8.8950686968504087	0.2741413878832342	0.1096613565613538	0.2741413878832342	
+0.1180000000000000	-0.2569736127659462	-0.6444882288042375	8.8876746790906758	0.2741411425692848	0.1096613408610299	0.2741411425692848	
+0.1190000000000000	-0.2592735523875824	-0.6499705557979344	8.8802875977171762	0.2741408951676310	0.1096613250270870	0.2741408951676310	
+0.1200000000000000	-0.2615753538231487	-0.6554521415261635	8.8729074806773127	0.2741406456782751	0.1096613090595251	0.2741406456782751	
+0.1210000000000000	-0.2638790153709539	-0.6609329486974564	8.8655343558670978	0.2741403941012187	0.1096612929583443	0.2741403941012187	
+0.1220000000000000	-0.2661845353047114	-0.6664129400065715	8.8581682511310245	0.2741401404364637	0.1096612767235444	0.2741401404364637	
+0.1230000000000000	-0.2684919118735276	-0.6718920781346849	8.8508091942619647	0.2741398846840123	0.1096612603551257	0.2741398846840123	
+0.1240000000000000	-0.2708011433018874	-0.6773703257495785	8.8434572130010540	0.2741396268438663	0.1096612438530880	0.2741396268438663	
+0.1250000000000000	-0.2731122277896427	-0.6828476455058294	8.8361123350375887	0.2741393669160276	0.1096612272174314	0.2741393669160276	
+0.1260000000000000	-0.2754251635119989	-0.6883240000449991	8.8287745880088906	0.2741391049004983	0.1096612104481559	0.2741391049004983	
+0.1270000000000000	-0.2777399486195025	-0.6937993519958234	8.8214439995002234	0.2741388407972802	0.1096611935452616	0.2741388407972802	
+0.1280000000000000	-0.2800565812380301	-0.6992736639744029	8.8141205970446688	0.2741385746063755	0.1096611765087484	0.2741385746063755	
+0.1290000000000000	-0.2823750594687746	-0.7047468985843905	8.8068044081230141	0.2741383063277862	0.1096611593386164	0.2741383063277862	
+0.1300000000000000	-0.2846953813882340	-0.7102190184171832	8.7994954601636390	0.2741380359615143	0.1096611420348656	0.2741380359615143	
+0.1310000000000000	-0.2870175450482002	-0.7156899860521118	8.7921937805424175	0.2741377635075619	0.1096611245974960	0.2741377635075619	
+0.1320000000000000	-0.2893415484757468	-0.7211597640566301	8.7848993965825990	0.2741374889659310	0.1096611070265077	0.2741374889659310	
+0.1330000000000000	-0.2916673896732177	-0.7266283149865055	8.7776123355546982	0.2741372123366237	0.1096610893219006	0.2741372123366237	
+0.1340000000000000	-0.2939950666182164	-0.7320956013860096	8.7703326246763975	0.2741369336196423	0.1096610714836749	0.2741369336196423	
+0.1350000000000000	-0.2963245772635942	-0.7375615857881097	8.7630602911124136	0.2741366528149887	0.1096610535118304	0.2741366528149887	
+0.1360000000000000	-0.2986559195374403	-0.7430262307146571	8.7557953619744158	0.2741363699226650	0.1096610354063673	0.2741363699226650	
+0.1370000000000000	-0.3009890913430705	-0.7484894986765788	8.7485378643209089	0.2741360849426736	0.1096610171672855	0.2741360849426736	
+0.1380000000000000	-0.3033240905590167	-0.7539513521740693	8.7412878251571140	0.2741357978750164	0.1096609987945851	0.2741357978750164	
+0.1390000000000000	-0.3056609150390163	-0.7594117536967799	8.7340452714348675	0.2741355087196958	0.1096609802882661	0.2741355087196958	
+0.1400000000000000	-0.3079995626120035	-0.7648706657240107	8.7268102300525321	0.2741352174767139	0.1096609616483285	0.2741352174767139	
+0.1410000000000000	-0.3103400310820976	-0.7703280507249010	8.7195827278548617	0.2741349241460729	0.1096609428747724	0.2741349241460729	
+0.1420000000000000	-0.3126823182285942	-0.7757838711586220	8.7123627916329127	0.2741346287277751	0.1096609239675977	0.2741346287277751	
+0.1430000000000000	-0.3150264218059549	-0.7812380894745659	8.7051504481239252	0.2741343312218228	0.1096609049268045	0.2741343312218228	
+0.1440000000000000	-0.3173723395437987	-0.7866906681125396	8.6979457240112268	0.2741340316282180	0.1096608857523929	0.2741340316282180	
+0.1450000000000000	-0.3197200691468921	-0.7921415695029539	8.6907486459241241	0.2741337299469633	0.1096608664443627	0.2741337299469633	
+0.1460000000000000	-0.3220696082951404	-0.7975907560670172	8.6835592404378019	0.2741334261780609	0.1096608470027142	0.2741334261780609	
+0.1470000000000000	-0.3244209546435783	-0.8030381902169265	8.6763775340732074	0.2741331203215130	0.1096608274274472	0.2741331203215130	
+0.1480000000000000	-0.3267741058223620	-0.8084838343560588	8.6692035532969456	0.2741328123773220	0.1096608077185618	0.2741328123773220	
+0.1490000000000000	-0.3291290594367595	-0.8139276508791634	8.6620373245211972	0.2741325023454903	0.1096607878760580	0.2741325023454903	
+0.1500000000000000	-0.3314858130671436	-0.8193696021725538	8.6548788741035843	0.2741321902260201	0.1096607678999359	0.2741321902260201	
+0.1510000000000000	-0.3338443642689825	-0.8248096506143008	8.6477282283470824	0.2741318760189140	0.1096607477901955	0.2741318760189140	
+0.1520000000000000	-0.3362047105728325	-0.8302477585744228	8.6405854134999220	0.2741315597241742	0.1096607275468368	0.2741315597241742	
+0.1530000000000000	-0.3385668494843301	-0.8356838884150801	8.6334504557554723	0.2741312413418034	0.1096607071698598	0.2741312413418034	
+0.1540000000000000	-0.3409307784841841	-0.8411180024907660	8.6263233812521420	0.2741309208718036	0.1096606866592646	0.2741309208718036	
+0.1550000000000000	-0.3432964950281682	-0.8465500631484996	8.6192042160732925	0.2741305983141775	0.1096606660150511	0.2741305983141775	
+0.1560000000000000	-0.3456639965471137	-0.8519800327280189	8.6120929862471041	0.2741302736689276	0.1096606452372194	0.2741302736689276	
+0.1570000000000000	-0.3480332804469027	-0.8574078735619730	8.6049897177465056	0.2741299469360562	0.1096606243257696	0.2741299469360562	
+0.1580000000000000	-0.3504043441084608	-0.8628335479761160	8.5978944364890548	0.2741296181155659	0.1096606032807017	0.2741296181155659	
+0.1590000000000000	-0.3527771848877503	-0.8682570182894966	8.5908071683368483	0.2741292872074591	0.1096605821020155	0.2741292872074591	
+0.1600000000000000	-0.3551518001157639	-0.8736782468146560	8.5837279390964003	0.2741289542117386	0.1096605607897114	0.2741289542117386	
+0.1610000000000000	-0.3575281870985184	-0.8790971958578168	8.5766567745185807	0.2741286191284065	0.1096605393437891	0.2741286191284065	
+0.1620000000000000	-0.3599063431170482	-0.8845138277190785	8.5695937002984657	0.2741282819574657	0.1096605177642488	0.2741282819574657	
+0.1630000000000000	-0.3622862654273989	-0.8899281046926091	8.5625387420752741	0.2741279426989187	0.1096604960510905	0.2741279426989187	
+0.1640000000000000	-0.3646679512606228	-0.8953399890668396	8.5554919254322641	0.2741276013527679	0.1096604742043142	0.2741276013527679	
+0.1650000000000000	-0.3670513978227715	-0.9007494431246579	8.5484532758966125	0.2741272579190162	0.1096604522239199	0.2741272579190162	
+0.1660000000000000	-0.3694366022948915	-0.9061564291435994	8.5414228189393384	0.2741269123976659	0.1096604301099078	0.2741269123976659	
+0.1670000000000000	-0.3718235618330192	-0.9115609093960459	8.5344005799751983	0.2741265647887198	0.1096604078622777	0.2741265647887198	
+0.1680000000000000	-0.3742122735681742	-0.9169628461494113	8.5273865843625813	0.2741262150921807	0.1096603854810296	0.2741262150921807	
+0.1690000000000000	-0.3766027346063561	-0.9223622016663440	8.5203808574034081	0.2741258633080509	0.1096603629661638	0.2741258633080509	
+0.1700000000000000	-0.3789949420285387	-0.9277589382049141	8.5133834243430595	0.2741255094363333	0.1096603403176801	0.2741255094363333	
+0.1710000000000000	-0.3813888928906660	-0.9331530180188108	8.5063943103702453	0.2741251534770306	0.1096603175355787	0.2741251534770306	
+0.1720000000000000	-0.3837845842236468	-0.9385444033575352	8.4994135406169260	0.2741247954301455	0.1096602946198594	0.2741247954301455	
+0.1730000000000000	-0.3861820130333522	-0.9439330564665946	8.4924411401582223	0.2741244352956806	0.1096602715705224	0.2741244352956806	
+0.1740000000000000	-0.3885811763006098	-0.9493189395876962	8.4854771340122959	0.2741240730736389	0.1096602483875677	0.2741240730736389	
+0.1750000000000000	-0.3909820709812011	-0.9547020149589410	8.4785215471402822	0.2741237087640229	0.1096602250709953	0.2741237087640229	
+0.1760000000000000	-0.3933846940058571	-0.9600822448150197	8.4715744044461658	0.2741233423668356	0.1096602016208053	0.2741233423668356	
+0.1770000000000000	-0.3957890422802546	-0.9654595913874047	8.4646357307767062	0.2741229738820796	0.1096601780369976	0.2741229738820796	
+0.1780000000000000	-0.3981951126850138	-0.9708340169045464	8.4577055509213341	0.2741226033097577	0.1096601543195723	0.2741226033097577	
+0.1790000000000000	-0.4006029020756949	-0.9762054835920669	8.4507838896120671	0.2741222306498729	0.1096601304685295	0.2741222306498729	
+0.1800000000000000	-0.4030124072827945	-0.9815739536729526	8.4438707715233878	0.2741218559024279	0.1096601064838691	0.2741218559024279	
+0.1810000000000000	-0.4054236251117432	-0.9869393893677544	8.4369662212721934	0.2741214790674256	0.1096600823655911	0.2741214790674256	
+0.1820000000000000	-0.4078365523429037	-0.9923017528947751	8.4300702634176581	0.2741211001448688	0.1096600581136957	0.2741211001448688	
+0.1830000000000000	-0.4102511857315672	-0.9976610064702690	8.4231829224611694	0.2741207191347605	0.1096600337281829	0.2741207191347605	
+0.1840000000000000	-0.4126675220079519	-1.0030171123086356	8.4163042228462217	0.2741203360371036	0.1096600092090526	0.2741203360371036	
+0.1850000000000000	-0.4150855578772015	-1.0083700326226133	8.4094341889583397	0.2741199508519008	0.1096599845563049	0.2741199508519008	
+0.1860000000000000	-0.4175052900193814	-1.0137197296234759	8.4025728451249471	0.2741195635791553	0.1096599597699399	0.2741195635791553	
+0.1870000000000000	-0.4199267150894797	-1.0190661655212274	8.3957202156153325	0.2741191742188701	0.1096599348499575	0.2741191742188701	
+0.1880000000000000	-0.4223498297174038	-1.0244093025247942	8.3888763246405045	0.2741187827710478	0.1096599097963578	0.2741187827710478	
+0.1890000000000000	-0.4247746305079793	-1.0297491028422239	8.3820411963531356	0.2741183892356917	0.1096598846091408	0.2741183892356917	
+0.1900000000000000	-0.4272011140409498	-1.0350855286808796	8.3752148548474494	0.2741179936128046	0.1096598592883067	0.2741179936128046	
+0.1910000000000000	-0.4296292768709752	-1.0404185422476326	8.3683973241591492	0.2741175959023897	0.1096598338338552	0.2741175959023897	
+0.1920000000000000	-0.4320591155276312	-1.0457481057490612	8.3615886282653111	0.2741171961044498	0.1096598082457866	0.2741171961044498	
+0.1930000000000000	-0.4344906265154088	-1.0510741813916429	8.3547887910843048	0.2741167942189882	0.1096597825241009	0.2741167942189882	
+0.1940000000000000	-0.4369238063137135	-1.0563967313819520	8.3479978364756882	0.2741163902460078	0.1096597566687980	0.2741163902460078	
+0.1950000000000000	-0.4393586513768659	-1.0617157179268535	8.3412157882401541	0.2741159841855117	0.1096597306798780	0.2741159841855117	
+0.1960000000000000	-0.4417951581341008	-1.0670311032336999	8.3344426701193957	0.2741155760375030	0.1096597045573410	0.2741155760375030	
+0.1970000000000000	-0.4442333229895680	-1.0723428495105254	8.3276785057960492	0.2741151658019848	0.1096596783011870	0.2741151658019848	
+0.1980000000000000	-0.4466731423223325	-1.0776509189662415	8.3209233188935929	0.2741147534789603	0.1096596519114159	0.2741147534789603	
+0.1990000000000000	-0.4491146124863749	-1.0829552738108350	8.3141771329762673	0.2741143390684325	0.1096596253880279	0.2741143390684325	
+0.2000000000000000	-0.4515577298105923	-1.0882558762555596	8.3074399715489822	0.2741139225704047	0.1096595987310230	0.2741139225704047	
+0.2010000000000000	-0.4540024905987988	-1.0935526885131348	8.3007118580572214	0.2741135039848800	0.1096595719404012	0.2741135039848800	
+0.2020000000000000	-0.4564488911297273	-1.0988456727979401	8.2939928158869751	0.2741130833118616	0.1096595450161625	0.2741130833118616	
+0.2030000000000000	-0.4588969276570307	-1.1041347913262127	8.2872828683646453	0.2741126605513526	0.1096595179583070	0.2741126605513526	
+0.2040000000000000	-0.4613465964092821	-1.1094200063162400	8.2805820387569469	0.2741122357033564	0.1096594907668347	0.2741122357033564	
+0.2050000000000000	-0.4637978935899785	-1.1147012799885589	8.2738903502708396	0.2741118087678762	0.1096594634417456	0.2741118087678762	
+0.2060000000000000	-0.4662508153775408	-1.1199785745661495	8.2672078260534381	0.2741113797449151	0.1096594359830398	0.2741113797449151	
+0.2070000000000000	-0.4687053579253172	-1.1252518522746318	8.2605344891919188	0.2741109486344765	0.1096594083907173	0.2741109486344765	
+0.2080000000000000	-0.4711615173615840	-1.1305210753424602	8.2538703627134371	0.2741105154365637	0.1096593806647781	0.2741105154365637	
+0.2090000000000000	-0.4736192897895494	-1.1357862060011235	8.2472154695850612	0.2741100801511799	0.1096593528052223	0.2741100801511799	
+0.2100000000000000	-0.4760786712873554	-1.1410472064853376	8.2405698327136552	0.2741096427783285	0.1096593248120499	0.2741096427783285	
+0.2110000000000000	-0.4785396579080804	-1.1463040390332409	8.2339334749458288	0.2741092033180129	0.1096592966852609	0.2741092033180129	
+0.2120000000000000	-0.4810022456797425	-1.1515566658865934	8.2273064190678298	0.2741087617702361	0.1096592684248555	0.2741087617702361	
+0.2130000000000000	-0.4834664306053023	-1.1568050492909707	8.2206886878054704	0.2741083181350019	0.1096592400308335	0.2741083181350019	
+0.2140000000000000	-0.4859322086626667	-1.1620491514959608	8.2140803038240531	0.2741078724123134	0.1096592115031950	0.2741078724123134	
+0.2150000000000000	-0.4883995758046921	-1.1672889347553612	8.2074812897282676	0.2741074246021741	0.1096591828419402	0.2741074246021741	
+0.2160000000000000	-0.4908685279591877	-1.1725243613273730	8.2008916680621233	0.2741069747045874	0.1096591540470689	0.2741069747045874	
+0.2170000000000000	-0.4933390610289208	-1.1777553934747997	8.1943114613088746	0.2741065227195568	0.1096591251185813	0.2741065227195568	
+0.2180000000000000	-0.4958111708916185	-1.1829819934652415	8.1877406918909177	0.2741060686470855	0.1096590960564774	0.2741060686470855	
+0.2190000000000000	-0.4982848533999741	-1.1882041235712930	8.1811793821697272	0.2741056124871772	0.1096590668607572	0.2741056124871772	
+0.2200000000000000	-0.5007601043816508	-1.1934217460707384	8.1746275544457703	0.2741051542398353	0.1096590375314207	0.2741051542398353	
+0.2210000000000000	-0.5032369196392859	-1.1986348232467481	8.1680852309584271	0.2741046939050633	0.1096590080684680	0.2741046939050633	
+0.2220000000000000	-0.5057152949504959	-1.2038433173880771	8.1615524338859036	0.2741042314828646	0.1096589784718992	0.2741042314828646	
+0.2230000000000000	-0.5081952260678819	-1.2090471907892588	8.1550291853451640	0.2741037669732428	0.1096589487417142	0.2741037669732428	
+0.2240000000000000	-0.5106767087190347	-1.2142464057508022	8.1485155073918527	0.2741033003762016	0.1096589188779131	0.2741033003762016	
+0.2250000000000000	-0.5131597386065390	-1.2194409245793891	8.1420114220201967	0.2741028316917442	0.1096588888804959	0.2741028316917442	
+0.2260000000000000	-0.5156443114079805	-1.2246307095880691	8.1355169511629430	0.2741023609198745	0.1096588587494627	0.2741023609198745	
+0.2270000000000000	-0.5181304227759511	-1.2298157230964595	8.1290321166912829	0.2741018880605959	0.1096588284848136	0.2741018880605959	
+0.2280000000000000	-0.5206180683380541	-1.2349959274309370	8.1225569404147553	0.2741014131139121	0.1096587980865484	0.2741014131139121	
+0.2290000000000000	-0.5231072436969118	-1.2401712849248381	8.1160914440811993	0.2741009360798267	0.1096587675546674	0.2741009360798267	
+0.2300000000000000	-0.5255979444301697	-1.2453417579186532	8.1096356493766351	0.2741004569583432	0.1096587368891704	0.2741004569583432	
+0.2310000000000000	-0.5280901660905056	-1.2505073087602256	8.1031895779252388	0.2740999757494654	0.1096587060900576	0.2740999757494654	
+0.2320000000000000	-0.5305839042056343	-1.2556678998049455	8.0967532512892237	0.2740994924531969	0.1096586751573290	0.2740994924531969	
+0.2330000000000000	-0.5330791542783143	-1.2608234934159483	8.0903266909687748	0.2740990070695414	0.1096586440909846	0.2740990070695414	
+0.2340000000000000	-0.5355759117863570	-1.2659740519643101	8.0839099184019965	0.2740985195985027	0.1096586128910245	0.2740985195985027	
+0.2350000000000000	-0.5380741721826314	-1.2711195378292475	8.0775029549647925	0.2740980300400843	0.1096585815574487	0.2740980300400843	
+0.2360000000000000	-0.5405739308950732	-1.2762599133983070	8.0711058219708427	0.2740975383942900	0.1096585500902573	0.2740975383942900	
+0.2370000000000000	-0.5430751833266915	-1.2813951410675704	8.0647185406714836	0.2740970446611236	0.1096585184894502	0.2740970446611236	
+0.2380000000000000	-0.5455779248555774	-1.2865251832418454	8.0583411322556664	0.2740965488405889	0.1096584867550275	0.2740965488405889	
+0.2390000000000000	-0.5480821508349113	-1.2916500023348647	8.0519736178498569	0.2740960509326896	0.1096584548869894	0.2740960509326896	
+0.2400000000000000	-0.5505878565929712	-1.2967695607694818	8.0456160185179844	0.2740955509374295	0.1096584228853356	0.2740955509374295	
+0.2410000000000000	-0.5530950374331414	-1.3018838209778687	8.0392683552613597	0.2740950488548124	0.1096583907500665	0.2740950488548124	
+0.2420000000000000	-0.5556036886339208	-1.3069927454017121	8.0329306490185921	0.2740945446848421	0.1096583584811819	0.2740945446848421	
+0.2430000000000000	-0.5581138054489309	-1.3120962964924061	8.0266029206655247	0.2740940384275226	0.1096583260786819	0.2740940384275226	
+0.2440000000000000	-0.5606253831069264	-1.3171944367112580	8.0202851910151818	0.2740935300828574	0.1096582935425666	0.2740935300828574	
+0.2450000000000000	-0.5631384168118030	-1.3222871285296758	8.0139774808176547	0.2740930196508509	0.1096582608728360	0.2740930196508509	
+0.2460000000000000	-0.5656529017426067	-1.3273743344293694	8.0076798107600720	0.2740925071315065	0.1096582280694901	0.2740925071315065	
+0.2470000000000000	-0.5681688330535442	-1.3324560169025463	8.0013922014665013	0.2740919925248283	0.1096581951325290	0.2740919925248283	
+0.2480000000000000	-0.5706862058739917	-1.3375321384521097	7.9951146734978975	0.2740914758308202	0.1096581620619527	0.2740914758308202	
+0.2490000000000000	-0.5732050153085049	-1.3426026615918516	7.9888472473520054	0.2740909570494863	0.1096581288577612	0.2740909570494863	
+0.2500000000000000	-0.5757252564368294	-1.3476675488466527	7.9825899434633234	0.2740904361808303	0.1096580955199547	0.2740904361808303	
+0.2510000000000000	-0.5782469243139112	-1.3527267627526787	7.9763427822030186	0.2740899132248562	0.1096580620485331	0.2740899132248562	
+0.2520000000000000	-0.5807700139699056	-1.3577802658575742	7.9701057838788367	0.2740893881815681	0.1096580284434965	0.2740893881815681	
+0.2530000000000000	-0.5832945204101893	-1.3628280207206631	7.9638789687350684	0.2740888610509700	0.1096579947048448	0.2740888610509700	
+0.2540000000000000	-0.5858204386153709	-1.3678699899131421	7.9576623569524640	0.2740883318330657	0.1096579608325783	0.2740883318330657	
+0.2550000000000000	-0.5883477635413018	-1.3729061360182790	7.9514559686481627	0.2740878005278595	0.1096579268266968	0.2740878005278595	
+0.2560000000000000	-0.5908764901190868	-1.3779364216316090	7.9452598238756265	0.2740872671353554	0.1096578926872005	0.2740872671353554	
+0.2570000000000000	-0.5934066132550964	-1.3829608093611303	7.9390739426245762	0.2740867316555574	0.1096578584140893	0.2740867316555574	
+0.2580000000000000	-0.5959381278309774	-1.3879792618275029	7.9328983448209236	0.2740861940884695	0.1096578240073634	0.2740861940884695	
+0.2590000000000000	-0.5984710287036659	-1.3929917416642414	7.9267330503266997	0.2740856544340958	0.1096577894670228	0.2740856544340958	
+0.2600000000000000	-0.6010053107053974	-1.3979982115179161	7.9205780789399940	0.2740851126924406	0.1096577547930674	0.2740851126924406	
+0.2610000000000000	-0.6035409686437209	-1.4029986340483456	7.9144334503948830	0.2740845688635078	0.1096577199854975	0.2740845688635078	
+0.2620000000000000	-0.6060779973015096	-1.4079929719287947	7.9082991843613719	0.2740840229473018	0.1096576850443128	0.2740840229473018	
+0.2630000000000000	-0.6086163914369744	-1.4129811878461727	7.9021753004453226	0.2740834749438265	0.1096576499695137	0.2740834749438265	
+0.2640000000000000	-0.6111561457836761	-1.4179632445012265	7.8960618181883904	0.2740829248530862	0.1096576147611000	0.2740829248530862	
+0.2650000000000000	-0.6136972550505376	-1.4229391046087376	7.8899587570679550	0.2740823726750851	0.1096575794190718	0.2740823726750851	
+0.2660000000000000	-0.6162397139218587	-1.4279087308977223	7.8838661364970690	0.2740818184098273	0.1096575439434292	0.2740818184098273	
+0.2670000000000000	-0.6187835170573281	-1.4328720861116238	7.8777839758243795	0.2740812620573171	0.1096575083341722	0.2740812620573171	
+0.2680000000000000	-0.6213286590920368	-1.4378291330085096	7.8717122943340732	0.2740807036175588	0.1096574725913009	0.2740807036175588	
+0.2690000000000000	-0.6238751346364917	-1.4427798343612697	7.8656511112458105	0.2740801430905566	0.1096574367148153	0.2740801430905566	
+0.2700000000000000	-0.6264229382766304	-1.4477241529578082	7.8596004457146602	0.2740795804763146	0.1096574007047154	0.2740795804763146	
+0.2710000000000000	-0.6289720645738341	-1.4526620516012478	7.8535603168310448	0.2740790157748373	0.1096573645610012	0.2740790157748373	
+0.2720000000000000	-0.6315225080649416	-1.4575934931101151	7.8475307436206698	0.2740784489861290	0.1096573282836730	0.2740784489861290	
+0.2730000000000000	-0.6340742632622647	-1.4625184403185474	7.8415117450444587	0.2740778801101939	0.1096572918727305	0.2740778801101939	
+0.2740000000000000	-0.6366273246536019	-1.4674368560764823	7.8355033399985023	0.2740773091470364	0.1096572553281740	0.2740773091470364	
+0.2750000000000000	-0.6391816867022539	-1.4723487032498546	7.8295055473140023	0.2740767360966609	0.1096572186500035	0.2740767360966609	
+0.2760000000000000	-0.6417373438470377	-1.4772539447207955	7.8235183857571888	0.2740761609590716	0.1096571818382189	0.2740761609590716	
+0.2770000000000000	-0.6442942905023024	-1.4821525433878255	7.8175418740292777	0.2740755837342730	0.1096571448928204	0.2740755837342730	
+0.2780000000000000	-0.6468525210579433	-1.4870444621660517	7.8115760307663997	0.2740750044222695	0.1096571078138080	0.2740750044222695	
+0.2790000000000000	-0.6494120298794197	-1.4919296639873629	7.8056208745395574	0.2740744230230655	0.1096570706011818	0.2740744230230655	
+0.2800000000000000	-0.6519728113077679	-1.4968081118006284	7.7996764238545433	0.2740738395366653	0.1096570332549417	0.2740738395366653	
+0.2810000000000000	-0.6545348596596190	-1.5016797685718899	7.7937426971518988	0.2740732539630736	0.1096569957750878	0.2740732539630736	
+0.2820000000000000	-0.6570981692272138	-1.5065445972845590	7.7878197128068489	0.2740726663022947	0.1096569581616202	0.2740726663022947	
+0.2830000000000000	-0.6596627342784200	-1.5114025609396138	7.7819074891292450	0.2740720765543330	0.1096569204145390	0.2740720765543330	
+0.2840000000000000	-0.6622285490567477	-1.5162536225557961	7.7760060443635002	0.2740714847191931	0.1096568825338441	0.2740714847191931	
+0.2850000000000000	-0.6647956077813665	-1.5210977451698016	7.7701153966885421	0.2740708907968795	0.1096568445195356	0.2740708907968795	
+0.2860000000000000	-0.6673639046471229	-1.5259348918364823	7.7642355642177590	0.2740702947873968	0.1096568063716136	0.2740702947873968	
+0.2870000000000000	-0.6699334338245551	-1.5307650256290377	7.7583665649989193	0.2740696966907493	0.1096567680900781	0.2740696966907493	
+0.2880000000000000	-0.6725041894599133	-1.5355881096392112	7.7525084170141429	0.2740690965069418	0.1096567296749291	0.2740690965069418	
+0.2890000000000000	-0.6750761656751743	-1.5404041069774879	7.7466611381798369	0.2740684942359787	0.1096566911261668	0.2740684942359787	
+0.2900000000000000	-0.6776493565680610	-1.5452129807732862	7.7408247463466182	0.2740678898778647	0.1096566524437911	0.2740678898778647	
+0.2910000000000000	-0.6802237562120597	-1.5500146941751580	7.7349992592993058	0.2740672834326044	0.1096566136278021	0.2740672834326044	
+0.2920000000000000	-0.6827993586564362	-1.5548092103509805	7.7291846947568104	0.2740666749002024	0.1096565746781998	0.2740666749002024	
+0.2930000000000000	-0.6853761579262567	-1.5595964924881502	7.7233810703721204	0.2740660642806633	0.1096565355949843	0.2740660642806633	
+0.2940000000000000	-0.6879541480224041	-1.5643765037937847	7.7175884037322238	0.2740654515739917	0.1096564963781557	0.2740654515739917	
+0.2950000000000000	-0.6905333229215975	-1.5691492074949127	7.7118067123580687	0.2740648367801924	0.1096564570277139	0.2740648367801924	
+0.2960000000000000	-0.6931136765764110	-1.5739145668386685	7.7060360137045123	0.2740642198992700	0.1096564175436591	0.2740642198992700	
+0.2970000000000000	-0.6956952029152910	-1.5786725450924901	7.7002763251602495	0.2740636009312292	0.1096563779259912	0.2740636009312292	
+0.2980000000000000	-0.6982778958425776	-1.5834231055443158	7.6945276640477740	0.2740629798760748	0.1096563381747104	0.2740629798760748	
+0.2990000000000000	-0.7008617492385221	-1.5881662115027706	7.6887900476233275	0.2740623567338114	0.1096562982898166	0.2740623567338114	
+0.3000000000000000	-0.7034467569593067	-1.5929018262973733	7.6830634930768369	0.2740617315044437	0.1096562582713100	0.2740617315044437	
+0.3010000000000000	-0.7060329128370643	-1.5976299132787219	7.6773480175318696	0.2740611041879767	0.1096562181191906	0.2740611041879767	
+0.3020000000000000	-0.7086202106798993	-1.6023504358186935	7.6716436380455892	0.2740604747844150	0.1096561778334584	0.2740604747844150	
+0.3030000000000000	-0.7112086442719061	-1.6070633573106350	7.6659503716086874	0.2740598432937634	0.1096561374141134	0.2740598432937634	
+0.3040000000000000	-0.7137982073731891	-1.6117686411695646	7.6602682351453435	0.2740592097160268	0.1096560968611558	0.2740592097160268	
+0.3050000000000000	-0.7163888937198851	-1.6164662508323571	7.6545972455131821	0.2740585740512099	0.1096560561745855	0.2740585740512099	
+0.3060000000000000	-0.7189806970241817	-1.6211561497579452	7.6489374195032074	0.2740579362993177	0.1096560153544027	0.2740579362993177	
+0.3070000000000000	-0.7215736109743389	-1.6258383014275144	7.6432887738397604	0.2740572964603549	0.1096559744006073	0.2740572964603549	
+0.3080000000000000	-0.7241676292347110	-1.6305126693446923	7.6376513251804727	0.2740566545343265	0.1096559333131995	0.2740566545343265	
+0.3090000000000000	-0.7267627454457652	-1.6351792170357480	7.6320250901162172	0.2740560105212373	0.1096558920921792	0.2740560105212373	
+0.3100000000000000	-0.7293589532241056	-1.6398379080497836	7.6264100851710541	0.2740553644210922	0.1096558507375465	0.2740553644210922	
+0.3110000000000000	-0.7319562461624931	-1.6444887059589286	7.6208063268021853	0.2740547162338962	0.1096558092493015	0.2740547162338962	
+0.3120000000000000	-0.7345546178298672	-1.6491315743585355	7.6152138313999140	0.2740540659596541	0.1096557676274443	0.2740540659596541	
+0.3130000000000000	-0.7371540617713686	-1.6537664768673732	7.6096326152875839	0.2740534135983710	0.1096557258719748	0.2740534135983710	
+0.3140000000000000	-0.7397545715083607	-1.6583933771278212	7.6040626947215486	0.2740527591500518	0.1096556839828931	0.2740527591500518	
+0.3150000000000000	-0.7423561405384518	-1.6630122388060609	7.5985040858911113	0.2740521026147015	0.1096556419601993	0.2740521026147015	
+0.3160000000000000	-0.7449587623355172	-1.6676230255922753	7.5929568049184795	0.2740514439923251	0.1096555998038934	0.2740514439923251	
+0.3170000000000000	-0.7475624303497235	-1.6722257012008357	7.5874208678587314	0.2740507832829276	0.1096555575139755	0.2740507832829276	
+0.3180000000000000	-0.7501671380075488	-1.6768202293705017	7.5818962906997536	0.2740501204865140	0.1096555150904457	0.2740501204865140	
+0.3190000000000000	-0.7527728787118074	-1.6814065738646113	7.5763830893622135	0.2740494556030895	0.1096554725333039	0.2740494556030895	
+0.3200000000000000	-0.7553796458416728	-1.6859846984712745	7.5708812796995018	0.2740487886326589	0.1096554298425502	0.2740487886326589	
+0.3210000000000000	-0.7579874327527015	-1.6905545670035678	7.5653908774976877	0.2740481195752276	0.1096553870181847	0.2740481195752276	
+0.3220000000000000	-0.7605962327768538	-1.6951161432997282	7.5599118984754838	0.2740474484308004	0.1096553440602075	0.2740474484308004	
+0.3230000000000000	-0.7632060392225222	-1.6996693912233456	7.5544443582842007	0.2740467751993825	0.1096553009686186	0.2740467751993825	
+0.3240000000000000	-0.7658168453745506	-1.7042142746635545	7.5489882725076960	0.2740460998809791	0.1096552577434180	0.2740460998809791	
+0.3250000000000000	-0.7684286444942614	-1.7087507575352303	7.5435436566623331	0.2740454224755953	0.1096552143846057	0.2740454224755953	
+0.3260000000000000	-0.7710414298194795	-1.7132788037791806	7.5381105261969523	0.2740447429832363	0.1096551708921820	0.2740447429832363	
+0.3270000000000000	-0.7736551945645547	-1.7177983773623346	7.5326888964928109	0.2740440614039072	0.1096551272661467	0.2740440614039072	
+0.3280000000000000	-0.7762699319203888	-1.7223094422779459	7.5272787828635526	0.2740433777376133	0.1096550835065000	0.2740433777376133	
+0.3290000000000000	-0.7788856350544592	-1.7268119625457747	7.5218802005551559	0.2740426919843597	0.1096550396132419	0.2740426919843597	
+0.3300000000000000	-0.7815022971108445	-1.7313059022122852	7.5164931647459072	0.2740420041441516	0.1096549955863724	0.2740420041441516	
+0.3310000000000000	-0.7841199112102486	-1.7357912253508383	7.5111176905463450	0.2740413142169944	0.1096549514258917	0.2740413142169944	
+0.3320000000000000	-0.7867384704500275	-1.7402678960618843	7.5057537929992346	0.2740406222028932	0.1096549071317997	0.2740406222028932	
+0.3330000000000000	-0.7893579679042142	-1.7447358784731539	7.5004014870795128	0.2740399281018533	0.1096548627040965	0.2740399281018533	
+0.3340000000000000	-0.7919783966235441	-1.7491951367398493	7.4950607876942597	0.2740392319138800	0.1096548181427823	0.2740392319138800	
+0.3350000000000000	-0.7945997496354813	-1.7536456350448415	7.4897317096826512	0.2740385336389787	0.1096547734478569	0.2740385336389787	
+0.3360000000000000	-0.7972220199442461	-1.7580873375988570	7.4844142678159340	0.2740378332771545	0.1096547286193205	0.2740378332771545	
+0.3370000000000000	-0.7998452005308389	-1.7625202086406733	7.4791084767973723	0.2740371308284129	0.1096546836571732	0.2740371308284129	
+0.3380000000000000	-0.8024692843530680	-1.7669442124373069	7.4738143512622131	0.2740364262927592	0.1096546385614150	0.2740364262927592	
+0.3390000000000000	-0.8050942643455760	-1.7713593132842127	7.4685319057776551	0.2740357196701989	0.1096545933320459	0.2740357196701989	
+0.3400000000000000	-0.8077201334198673	-1.7757654755054650	7.4632611548427974	0.2740350109607371	0.1096545479690660	0.2740350109607371	
+0.3410000000000000	-0.8103468844643344	-1.7801626634539582	7.4580021128886234	0.2740343001643794	0.1096545024724754	0.2740343001643794	
+0.3420000000000000	-0.8129745103442851	-1.7845508415115927	7.4527547942779471	0.2740335872811312	0.1096544568422741	0.2740335872811312	
+0.3430000000000000	-0.8156030039019716	-1.7889299740894735	7.4475192133053820	0.2740328723109978	0.1096544110784621	0.2740328723109978	
+0.3440000000000000	-0.8182323579566150	-1.7933000256280895	7.4422953841973101	0.2740321552539848	0.1096543651810396	0.2740321552539848	
+0.3450000000000000	-0.8208625653044361	-1.7976609605975167	7.4370833211118281	0.2740314361100976	0.1096543191500066	0.2740314361100976	
+0.3460000000000000	-0.8234936187186818	-1.8020127434976039	7.4318830381387446	0.2740307148793417	0.1096542729853631	0.2740307148793417	
+0.3470000000000000	-0.8261255109496528	-1.8063553388581599	7.4266945492995129	0.2740299915617225	0.1096542266871092	0.2740299915617225	
+0.3480000000000000	-0.8287582347247349	-1.8106887112391545	7.4215178685472178	0.2740292661572457	0.1096541802552449	0.2740292661572457	
+0.3490000000000000	-0.8313917827484236	-1.8150128252308986	7.4163530097665262	0.2740285386659166	0.1096541336897703	0.2740285386659166	
+0.3500000000000000	-0.8340261477023558	-1.8193276454542409	7.4111999867736706	0.2740278090877408	0.1096540869906856	0.2740278090877408	
+0.3510000000000000	-0.8366613222453362	-1.8236331365607585	7.4060588133164007	0.2740270774227240	0.1096540401579906	0.2740270774227240	
+0.3520000000000000	-0.8392972990133687	-1.8279292632329445	7.4009295030739555	0.2740263436708716	0.1096539931916855	0.2740263436708716	
+0.3530000000000000	-0.8419340706196852	-1.8322159901843977	7.3958120696570351	0.2740256078321894	0.1096539460917704	0.2740256078321894	
+0.3540000000000000	-0.8445716296547738	-1.8364932821600188	7.3907065266077590	0.2740248699066827	0.1096538988582452	0.2740248699066827	
+0.3550000000000000	-0.8472099686864089	-1.8407611039361929	7.3856128873996472	0.2740241298943574	0.1096538514911101	0.2740241298943574	
+0.3560000000000000	-0.8498490802596823	-1.8450194203209853	7.3805311654375698	0.2740233877952188	0.1096538039903650	0.2740233877952188	
+0.3570000000000000	-0.8524889568970320	-1.8492681961543260	7.3754613740577426	0.2740226436092730	0.1096537563560102	0.2740226436092730	
+0.3580000000000000	-0.8551295910982725	-1.8535073963082049	7.3704035265276726	0.2740218973365254	0.1096537085880456	0.2740218973365254	
+0.3590000000000000	-0.8577709753406251	-1.8577369856868582	7.3653576360461379	0.2740211489769816	0.1096536606864712	0.2740211489769816	
+0.3600000000000000	-0.8604131020787488	-1.8619569292269569	7.3603237157431503	0.2740203985306475	0.1096536126512872	0.2740203985306475	
+0.3610000000000000	-0.8630559637447714	-1.8661671918978004	7.3553017786799426	0.2740196459975287	0.1096535644824936	0.2740196459975287	
+0.3620000000000000	-0.8656995527483200	-1.8703677387015003	7.3502918378489221	0.2740188913776310	0.1096535161800905	0.2740188913776310	
+0.3630000000000000	-0.8683438614765515	-1.8745585346731732	7.3452939061736506	0.2740181346709601	0.1096534677440778	0.2740181346709601	
+0.3640000000000000	-0.8709888822941845	-1.8787395448811293	7.3403079965088036	0.2740173758775217	0.1096534191744558	0.2740173758775217	
+0.3650000000000000	-0.8736346075435305	-1.8829107344270581	7.3353341216401633	0.2740166149973218	0.1096533704712244	0.2740166149973218	
+0.3660000000000000	-0.8762810295445271	-1.8870720684462232	7.3303722942845759	0.2740158520303659	0.1096533216343836	0.2740158520303659	
+0.3670000000000000	-0.8789281405947673	-1.8912235121076444	7.3254225270899251	0.2740150869766600	0.1096532726639336	0.2740150869766600	
+0.3680000000000000	-0.8815759329695325	-1.8953650306142884	7.3204848326351097	0.2740143198362099	0.1096532235598745	0.2740143198362099	
+0.3690000000000000	-0.8842243989218259	-1.8994965892032607	7.3155592234300091	0.2740135506090215	0.1096531743222062	0.2740135506090215	
+0.3700000000000000	-0.8868735306824033	-1.9036181531459861	7.3106457119154680	0.2740127792951004	0.1096531249509288	0.2740127792951004	
+0.3710000000000000	-0.8895233204598059	-1.9077296877484060	7.3057443104632664	0.2740120058944528	0.1096530754460424	0.2740120058944528	
+0.3720000000000000	-0.8921737604403948	-1.9118311583511596	7.3008550313760878	0.2740112304070844	0.1096530258075471	0.2740112304070844	
+0.3730000000000000	-0.8948248427883813	-1.9159225303297724	7.2959778868875018	0.2740104528330012	0.1096529760354429	0.2740104528330012	
+0.3740000000000000	-0.8974765596458611	-1.9200037690948473	7.2911128891619281	0.2740096731722090	0.1096529261297299	0.2740096731722090	
+0.3750000000000000	-0.9001289031328490	-1.9240748400922469	7.2862600502946391	0.2740088914247139	0.1096528760904081	0.2740088914247139	
+0.3760000000000000	-0.9027818653473105	-1.9281357088032891	7.2814193823116975	0.2740081075905216	0.1096528259174775	0.2740081075905216	
+0.3770000000000000	-0.9054354383651948	-1.9321863407449231	7.2765908971699602	0.2740073216696384	0.1096527756109384	0.2740073216696384	
+0.3780000000000000	-0.9080896142404723	-1.9362267014699246	7.2717746067570488	0.2740065336620700	0.1096527251707907	0.2740065336620700	
+0.3790000000000000	-0.9107443850051640	-1.9402567565670832	7.2669705228913148	0.2740057435678226	0.1096526745970344	0.2740057435678226	
+0.3800000000000000	-0.9133997426693798	-1.9442764716613830	7.2621786573218436	0.2740049513869021	0.1096526238896697	0.2740049513869021	
+0.3810000000000000	-0.9160556792213491	-1.9482858124141926	7.2573990217283955	0.2740041571193146	0.1096525730486966	0.2740041571193146	
+0.3820000000000000	-0.9187121866274588	-1.9522847445234550	7.2526316277214171	0.2740033607650661	0.1096525220741152	0.2740033607650661	
+0.3830000000000000	-0.9213692568322844	-1.9562732337238669	7.2478764868420029	0.2740025623241626	0.1096524709659255	0.2740025623241626	
+0.3840000000000000	-0.9240268817586292	-1.9602512457870709	7.2431336105618733	0.2740017617966104	0.1096524197241275	0.2740017617966104	
+0.3850000000000000	-0.9266850533075564	-1.9642187465218386	7.2384030102833634	0.2740009591824153	0.1096523683487215	0.2740009591824153	
+0.3860000000000000	-0.9293437633584246	-1.9681757017742578	7.2336846973393953	0.2740001544815838	0.1096523168397073	0.2740001544815838	
+0.3870000000000000	-0.9320030037689243	-1.9721220774279171	7.2289786829934615	0.2739993476941217	0.1096522651970851	0.2739993476941217	
+0.3880000000000000	-0.9346627663751130	-1.9760578394040909	7.2242849784396004	0.2739985388200352	0.1096522134208549	0.2739985388200352	
+0.3890000000000000	-0.9373230429914507	-1.9799829536619296	7.2196035948023862	0.2739977278593304	0.1096521615110169	0.2739977278593304	
+0.3900000000000000	-0.9399838254108366	-1.9838973861986371	7.2149345431368967	0.2739969148120138	0.1096521094675710	0.2739969148120138	
+0.3910000000000000	-0.9426451054046437	-1.9878011030496616	7.2102778344287053	0.2739960996780912	0.1096520572905174	0.2739960996780912	
+0.3920000000000000	-0.9453068747227589	-1.9916940702888808	7.2056334795938621	0.2739952824575690	0.1096520049798560	0.2739952824575690	
+0.3930000000000000	-0.9479691250936144	-1.9955762540287825	7.2010014894788696	0.2739944631504535	0.1096519525355870	0.2739944631504535	
+0.3940000000000000	-0.9506318482242276	-1.9994476204206522	7.1963818748606778	0.2739936417567508	0.1096518999577104	0.2739936417567508	
+0.3950000000000000	-0.9532950358002387	-2.0033081356547591	7.1917746464466443	0.2739928182764672	0.1096518472462263	0.2739928182764672	
+0.3960000000000000	-0.9559586794859447	-2.0071577659605357	7.1871798148745416	0.2739919927096089	0.1096517944011348	0.2739919927096089	
+0.3970000000000000	-0.9586227709243391	-2.0109964776067675	7.1825973907125338	0.2739911650561823	0.1096517414224359	0.2739911650561823	
+0.3980000000000000	-0.9612873017371477	-2.0148242369017719	7.1780273844591420	0.2739903353161937	0.1096516883101296	0.2739903353161937	
+0.3990000000000000	-0.9639522635248687	-2.0186410101935852	7.1734698065432649	0.2739895034896493	0.1096516350642161	0.2739895034896493	
+0.4000000000000000	-0.9666176478668074	-2.0224467638701467	7.1689246673241307	0.2739886695765555	0.1096515816846954	0.2739886695765555	
+0.4010000000000000	-0.9692834463211160	-2.0262414643594804	7.1643919770912969	0.2739878335769187	0.1096515281715676	0.2739878335769187	
+0.4020000000000000	-0.9719496504248317	-2.0300250781298783	7.1598717460646331	0.2739869954907453	0.1096514745248327	0.2739869954907453	
+0.4030000000000000	-0.9746162516939141	-2.0337975716900853	7.1553639843943131	0.2739861553180416	0.1096514207444908	0.2739861553180416	
+0.4040000000000000	-0.9772832416232841	-2.0375589115894810	7.1508687021607873	0.2739853130588139	0.1096513668305420	0.2739853130588139	
+0.4050000000000000	-0.9799506116868628	-2.0413090644182610	7.1463859093747795	0.2739844687130688	0.1096513127829863	0.2739844687130688	
+0.4060000000000000	-0.9826183533376107	-2.0450479968076261	7.1419156159772745	0.2739836222808126	0.1096512586018238	0.2739836222808126	
+0.4070000000000000	-0.9852864580075653	-2.0487756754299538	7.1374578318395017	0.2739827737620519	0.1096512042870546	0.2739827737620519	
+0.4080000000000000	-0.9879549171078814	-2.0524920669989930	7.1330125667629201	0.2739819231567930	0.1096511498386787	0.2739819231567930	
+0.4090000000000000	-0.9906237220288705	-2.0561971382700364	7.1285798304792136	0.2739810704650424	0.1096510952566962	0.2739810704650424	
+0.4100000000000000	-0.9932928641400403	-2.0598908560401075	7.1241596326502759	0.2739802156868067	0.1096510405411072	0.2739802156868067	
+0.4110000000000000	-0.9959623347901330	-2.0635731871481395	7.1197519828681965	0.2739793588220923	0.1096509856919117	0.2739793588220923	
+0.4120000000000000	-0.9986321253071679	-2.0672440984751623	7.1153568906552582	0.2739784998709058	0.1096509307091098	0.2739784998709058	
+0.4130000000000000	-1.0013022269984790	-2.0709035569444776	7.1109743654639104	0.2739776388332537	0.1096508755927015	0.2739776388332537	
+0.4140000000000000	-1.0039726311507562	-2.0745515295218420	7.1066044166767792	0.2739767757091425	0.1096508203426870	0.2739767757091425	
+0.4150000000000000	-1.0066433290300862	-2.0781879832156509	7.1022470536066464	0.2739759104985789	0.1096507649590664	0.2739759104985789	
+0.4160000000000000	-1.0093143118819914	-2.0818128850771185	7.0979022854964366	0.2739750432015695	0.1096507094418395	0.2739750432015695	
+0.4170000000000000	-1.0119855709314736	-2.0854262022004528	7.0935701215192211	0.2739741738181207	0.1096506537910066	0.2739741738181207	
+0.4180000000000000	-1.0146570973830513	-2.0890279017230458	7.0892505707781925	0.2739733023482393	0.1096505980065677	0.2739733023482393	
+0.4190000000000000	-1.0173288824208044	-2.0926179508256482	7.0849436423066718	0.2739724287919319	0.1096505420885229	0.2739724287919319	
+0.4200000000000000	-1.0200009172084123	-2.0961963167325486	7.0806493450680934	0.2739715531492051	0.1096504860368722	0.2739715531492051	
+0.4210000000000000	-1.0226731928891981	-2.0997629667117561	7.0763676879559965	0.2739706754200656	0.1096504298516158	0.2739706754200656	
+0.4220000000000000	-1.0253457005861677	-2.1033178680751803	7.0720986797940206	0.2739697956045202	0.1096503735327536	0.2739697956045202	
+0.4230000000000000	-1.0280184314020537	-2.1068609881788083	7.0678423293358970	0.2739689137025755	0.1096503170802857	0.2739689137025755	
+0.4240000000000000	-1.0306913764193568	-2.1103922944228861	7.0635986452654453	0.2739680297142381	0.1096502604942123	0.2739680297142381	
+0.4250000000000000	-1.0333645267003870	-2.1139117542521011	7.0593676361965647	0.2739671436395149	0.1096502037745333	0.2739671436395149	
+0.4260000000000000	-1.0360378732873063	-2.1174193351557529	7.0551493106732250	0.2739662554784126	0.1096501469212489	0.2739662554784126	
+0.4270000000000000	-1.0387114072021733	-2.1209150046679399	7.0509436771694682	0.2739653652309380	0.1096500899343591	0.2739653652309380	
+0.4280000000000000	-1.0413851194469825	-2.1243987303677345	7.0467507440894028	0.2739644728970977	0.1096500328138640	0.2739644728970977	
+0.4290000000000000	-1.0440590010037087	-2.1278704798793600	7.0425705197671959	0.2739635784768987	0.1096499755597637	0.2739635784768987	
+0.4300000000000000	-1.0467330428343509	-2.1313302208723739	7.0384030124670591	0.2739626819703478	0.1096499181720582	0.2739626819703478	
+0.4310000000000000	-1.0494072358809741	-2.1347779210618434	7.0342482303832741	0.2739617833774517	0.1096498606507476	0.2739617833774517	
+0.4320000000000000	-1.0520815710657538	-2.1382135482085229	7.0301061816401571	0.2739608826982173	0.1096498029958319	0.2739608826982173	
+0.4330000000000000	-1.0547560392910185	-2.1416370701190273	7.0259768742920681	0.2739599799326515	0.1096497452073114	0.2739599799326515	
+0.4340000000000000	-1.0574306314392929	-2.1450484546460200	7.0218603163234121	0.2739590750807612	0.1096496872851859	0.2739590750807612	
+0.4350000000000000	-1.0601053383733445	-2.1484476696883821	7.0177565156486441	0.2739581681425532	0.1096496292294556	0.2739581681425532	
+0.4360000000000000	-1.0627801509362258	-2.1518346831913924	7.0136654801122411	0.2739572591180344	0.1096495710401205	0.2739572591180344	
+0.4370000000000000	-1.0654550599513164	-2.1552094631469023	7.0095872174887237	0.2739563480072117	0.1096495127171808	0.2739563480072117	
+0.4380000000000000	-1.0681300562223723	-2.1585719775935170	7.0055217354826462	0.2739554348100923	0.1096494542606365	0.2739554348100923	
+0.4390000000000000	-1.0708051305335653	-2.1619221946167633	7.0014690417285905	0.2739545195266828	0.1096493956704876	0.2739545195266828	
+0.4400000000000000	-1.0734802736495317	-2.1652600823492776	6.9974291437911811	0.2739536021569903	0.1096493369467342	0.2739536021569903	
+0.4410000000000000	-1.0761554763154160	-2.1685856089709721	6.9934020491650681	0.2739526827010220	0.1096492780893765	0.2739526827010220	
+0.4420000000000000	-1.0788307292569137	-2.1718987427092169	6.9893877652749357	0.2739517611587846	0.1096492190984144	0.2739517611587846	
+0.4430000000000000	-1.0815060231803200	-2.1751994518390116	6.9853862994755023	0.2739508375302853	0.1096491599738481	0.2739508375302853	
+0.4440000000000000	-1.0841813487725735	-2.1784877046831630	6.9813976590515212	0.2739499118155310	0.1096491007156777	0.2739499118155310	
+0.4450000000000000	-1.0868566967013009	-2.1817634696124601	6.9774218512177768	0.2739489840145288	0.1096490413239031	0.2739489840145288	
+0.4460000000000000	-1.0895320576148648	-2.1850267150458484	6.9734588831190951	0.2739480541272858	0.1096489817985245	0.2739480541272858	
+0.4470000000000000	-1.0922074221424085	-2.1882774094506070	6.9695087618303395	0.2739471221538092	0.1096489221395419	0.2739471221538092	
+0.4480000000000000	-1.0948827808939017	-2.1915155213425206	6.9655714943564160	0.2739461880941058	0.1096488623469554	0.2739461880941058	
+0.4490000000000000	-1.0975581244601877	-2.1947410192860537	6.9616470876322687	0.2739452519481829	0.1096488024207652	0.2739452519481829	
+0.4500000000000000	-1.1002334434130294	-2.1979538718945268	6.9577355485228951	0.2739443137160477	0.1096487423609711	0.2739443137160477	
+0.4510000000000000	-1.1029087283051540	-2.2011540478302916	6.9538368838233415	0.2739433733977072	0.1096486821675735	0.2739433733977072	
+0.4520000000000000	-1.1055839696703038	-2.2043415158048982	6.9499511002586996	0.2739424309931686	0.1096486218405722	0.2739424309931686	
+0.4530000000000000	-1.1082591580232801	-2.2075162445792786	6.9460782044841363	0.2739414865024390	0.1096485613799674	0.2739414865024390	
+0.4540000000000000	-1.1109342838599912	-2.2106782029639098	6.9422182030848667	0.2739405399255258	0.1096485007857592	0.2739405399255258	
+0.4550000000000000	-1.1136093376574987	-2.2138273598189970	6.9383711025761796	0.2739395912624361	0.1096484400579475	0.2739395912624361	
+0.4560000000000000	-1.1162843098740669	-2.2169636840546350	6.9345369094034321	0.2739386405131771	0.1096483791965326	0.2739386405131771	
+0.4570000000000000	-1.1189591909492080	-2.2200871446309947	6.9307156299420658	0.2739376876777560	0.1096483182015145	0.2739376876777560	
+0.4580000000000000	-1.1216339713037324	-2.2231977105584813	6.9269072704976011	0.2739367327561802	0.1096482570728932	0.2739367327561802	
+0.4590000000000000	-1.1243086413397931	-2.2262953508979164	6.9231118373056493	0.2739357757484568	0.1096481958106688	0.2739357757484568	
+0.4600000000000000	-1.1269831914409392	-2.2293800347607098	6.9193293365319253	0.2739348166545932	0.1096481344148414	0.2739348166545932	
+0.4610000000000000	-1.1296576119721577	-2.2324517313090224	6.9155597742722339	0.2739338554745966	0.1096480728854111	0.2739338554745966	
+0.4620000000000000	-1.1323318932799264	-2.2355104097559475	6.9118031565525069	0.2739328922084746	0.1096480112223780	0.2739328922084746	
+0.4630000000000000	-1.1350060256922623	-2.2385560393656796	6.9080594893287897	0.2739319268562341	0.1096479494257420	0.2739319268562341	
+0.4640000000000000	-1.1376799995187681	-2.2415885894536833	6.9043287784872565	0.2739309594178828	0.1096478874955034	0.2739309594178828	
+0.4650000000000000	-1.1403538050506812	-2.2446080293868622	6.9006110298442067	0.2739299898934279	0.1096478254316622	0.2739299898934279	
+0.4660000000000000	-1.1430274325609262	-2.2476143285837376	6.8969062491460988	0.2739290182828769	0.1096477632342183	0.2739290182828769	
+0.4670000000000000	-1.1457008723041591	-2.2506074565146115	6.8932144420695352	0.2739280445862372	0.1096477009031721	0.2739280445862372	
+0.4680000000000000	-1.1483741145168218	-2.2535873827017392	6.8895356142212876	0.2739270688035159	0.1096476384385234	0.2739270688035159	
+0.4690000000000000	-1.1510471494171877	-2.2565540767195005	6.8858697711382959	0.2739260909347209	0.1096475758402724	0.2739260909347209	
+0.4700000000000000	-1.1537199672054126	-2.2595075081945675	6.8822169182876864	0.2739251109798593	0.1096475131084191	0.2739251109798593	
+0.4710000000000000	-1.1563925580635863	-2.2624476468060744	6.8785770610667818	0.2739241289389388	0.1096474502429637	0.2739241289389388	
+0.4720000000000000	-1.1590649121557806	-2.2653744622857896	6.8749502048031008	0.2739231448119667	0.1096473872439062	0.2739231448119667	
+0.4730000000000000	-1.1617370196280998	-2.2682879244182814	6.8713363547543898	0.2739221585989505	0.1096473241112466	0.2739221585989505	
+0.4740000000000000	-1.1644088706087321	-2.2711880030410860	6.8677355161086142	0.2739211702998979	0.1096472608449852	0.2739211702998979	
+0.4750000000000000	-1.1670804552079992	-2.2740746680448813	6.8641476939839876	0.2739201799148162	0.1096471974451218	0.2739201799148162	
+0.4760000000000000	-1.1697517635184074	-2.2769478893736492	6.8605728934289685	0.2739191874437131	0.1096471339116567	0.2739191874437131	
+0.4770000000000000	-1.1724227856146974	-2.2798076370248443	6.8570111194222836	0.2739181928865960	0.1096470702445899	0.2739181928865960	
+0.4780000000000000	-1.1750935115538979	-2.2826538810495727	6.8534623768729386	0.2739171962434727	0.1096470064439214	0.2739171962434727	
+0.4790000000000000	-1.1777639313753741	-2.2854865915527389	6.8499266706202295	0.2739161975143506	0.1096469425096514	0.2739161975143506	
+0.4800000000000000	-1.1804340351008789	-2.2883057386932322	6.8464040054337563	0.2739151966992374	0.1096468784417799	0.2739151966992374	
+0.4810000000000000	-1.1831038127346090	-2.2911112926840849	6.8428943860134446	0.2739141937981406	0.1096468142403070	0.2739141937981406	
+0.4820000000000000	-1.1857732542632502	-2.2939032237926429	6.8393978169895462	0.2739131888110681	0.1096467499052328	0.2739131888110681	
+0.4830000000000000	-1.1884423496560326	-2.2966815023407263	6.8359143029226725	0.2739121817380273	0.1096466854365574	0.2739121817380273	
+0.4840000000000000	-1.1911110888647833	-2.2994460987048004	6.8324438483037895	0.2739111725790259	0.1096466208342808	0.2739111725790259	
+0.4850000000000000	-1.1937794618239768	-2.3021969833161444	6.8289864575542447	0.2739101613340716	0.1096465560984031	0.2739101613340716	
+0.4860000000000000	-1.1964474584507874	-2.3049341266610113	6.8255421350257928	0.2739091480031722	0.1096464912289244	0.2739091480031722	
+0.4870000000000000	-1.1991150686451426	-2.3076574992807961	6.8221108850005834	0.2739081325863354	0.1096464262258448	0.2739081325863354	
+0.4880000000000000	-1.2017822822897759	-2.3103670717722018	6.8186927116912059	0.2739071150835689	0.1096463610891643	0.2739071150835689	
+0.4890000000000000	-1.2044490892502779	-2.3130628147874059	6.8152876192407001	0.2739060954948803	0.1096462958188831	0.2739060954948803	
+0.4900000000000000	-1.2071154793751508	-2.3157446990342221	6.8118956117225578	0.2739050738202776	0.1096462304150012	0.2739050738202776	
+0.4910000000000000	-1.2097814424958606	-2.3184126952762636	6.8085166931407537	0.2739040500597684	0.1096461648775187	0.2739040500597684	
+0.4920000000000000	-1.2124469684268919	-2.3210667743331159	6.8051508674297709	0.2739030242133607	0.1096460992064356	0.2739030242133607	
+0.4930000000000000	-1.2151120469657986	-2.3237069070804899	6.8017981384546031	0.2739019962810621	0.1096460334017521	0.2739019962810621	
+0.4940000000000000	-1.2177766678932596	-2.3263330644503930	6.7984585100107795	0.2739009662628805	0.1096459674634683	0.2739009662628805	
+0.4950000000000000	-1.2204408209731326	-2.3289452174312926	6.7951319858243906	0.2738999341588238	0.1096459013915841	0.2738999341588238	
+0.4960000000000000	-1.2231044959525061	-2.3315433370682737	6.7918185695520954	0.2738988999688998	0.1096458351860998	0.2738988999688998	
+0.4970000000000000	-1.2257676825617561	-2.3341273944632110	6.7885182647811559	0.2738978636931165	0.1096457688470153	0.2738978636931165	
+0.4980000000000000	-1.2284303705145976	-2.3366973607749211	6.7852310750294400	0.2738968253314816	0.1096457023743307	0.2738968253314816	
+0.4990000000000000	-1.2310925495081402	-2.3392532072193344	6.7819570037454593	0.2738957848840031	0.1096456357680463	0.2738957848840031	
+0.5000000000000000	-1.2337542092229434	-2.3417949050696532	6.7786960543083739	0.2738947423506889	0.1096455690281619	0.2738947423506889	
+0.5010000000000000	-1.2364153393230704	-2.3443224256565127	6.7754482300280383	0.2738936977315470	0.1096455021546777	0.2738936977315470	
+0.5020000000000000	-1.2390759294561415	-2.3468357403681450	6.7722135341449823	0.2738926510265852	0.1096454351475938	0.2738926510265852	
+0.5030000000000000	-1.2417359692533927	-2.3493348206505411	6.7689919698304806	0.2738916022358117	0.1096453680069103	0.2738916022358117	
+0.5040000000000000	-1.2443954483297259	-2.3518196380076071	6.7657835401865327	0.2738905513592343	0.1096453007326272	0.2738905513592343	
+0.5050000000000000	-1.2470543562837693	-2.3542901640013358	6.7625882482459172	0.2738894983968612	0.1096452333247446	0.2738894983968612	
+0.5060000000000000	-1.2497126826979299	-2.3567463702519529	6.7594060969722030	0.2738884433487002	0.1096451657832627	0.2738884433487002	
+0.5070000000000000	-1.2523704171384491	-2.3591882284380925	6.7562370892597627	0.2738873862147594	0.1096450981081814	0.2738873862147594	
+0.5080000000000000	-1.2550275491554599	-2.3616157102969444	6.7530812279338122	0.2738863269950469	0.1096450302995009	0.2738863269950469	
+0.5090000000000000	-1.2576840682830399	-2.3640287876244241	6.7499385157504301	0.2738852656895708	0.1096449623572213	0.2738852656895708	
+0.5100000000000000	-1.2603399640392712	-2.3664274322753238	6.7468089553965687	0.2738842022983391	0.1096448942813426	0.2738842022983391	
+0.5110000000000000	-1.2629952259262920	-2.3688116161634780	6.7436925494901043	0.2738831368213600	0.1096448260718649	0.2738831368213600	
+0.5120000000000000	-1.2656498434303600	-2.3711813112619229	6.7405893005798401	0.2738820692586414	0.1096447577287883	0.2738820692586414	
+0.5130000000000000	-1.2683038060218998	-2.3735364896030493	6.7374992111455425	0.2738809996101916	0.1096446892521129	0.2738809996101916	
+0.5140000000000000	-1.2709571031555682	-2.3758771232787668	6.7344222835979615	0.2738799278760187	0.1096446206418388	0.2738799278760187	
+0.5150000000000000	-1.2736097242703037	-2.3782031844406593	6.7313585202788682	0.2738788540561310	0.1096445518979660	0.2738788540561310	
+0.5160000000000000	-1.2762616587893889	-2.3805146453001456	6.7283079234610614	0.2738777781505365	0.1096444830204947	0.2738777781505365	
+0.5170000000000000	-1.2789128961205043	-2.3828114781286311	6.7252704953484130	0.2738767001592434	0.1096444140094249	0.2738767001592434	
+0.5180000000000000	-1.2815634256557875	-2.3850936552576769	6.7222462380758845	0.2738756200822600	0.1096443448647567	0.2738756200822600	
+0.5190000000000000	-1.2842132367718895	-2.3873611490791413	6.7192351537095591	0.2738745379195944	0.1096442755864902	0.2738745379195944	
+0.5200000000000000	-1.2868623188300321	-2.3896139320453496	6.7162372442466713	0.2738734536712550	0.1096442061746255	0.2738734536712550	
+0.5209999999999999	-1.2895106611760672	-2.3918519766692476	6.7132525116156341	0.2738723673372500	0.1096441366291626	0.2738723673372500	
+0.5220000000000000	-1.2921582531405322	-2.3940752555245544	6.7102809576760531	0.2738712789175877	0.1096440669501017	0.2738712789175877	
+0.5229999999999999	-1.2948050840387102	-2.3962837412459193	6.7073225842187849	0.2738701884122762	0.1096439971374428	0.2738701884122762	
+0.5240000000000000	-1.2974511431706870	-2.3984774065290804	6.7043773929659434	0.2738690958213240	0.1096439271911860	0.2738690958213240	
+0.5249999999999999	-1.3000964198214087	-2.4006562241310183	6.7014453855709295	0.2738680011447394	0.1096438571113314	0.2738680011447394	
+0.5260000000000000	-1.3027409032607418	-2.4028201668701126	6.6985265636184721	0.2738669043825307	0.1096437868978791	0.2738669043825307	
+0.5269999999999999	-1.3053845827435311	-2.4049692076262947	6.6956209286246597	0.2738658055347062	0.1096437165508292	0.2738658055347062	
+0.5280000000000000	-1.3080274475096587	-2.4071033193412052	6.6927284820369577	0.2738647046012744	0.1096436460701817	0.2738647046012744	
+0.5289999999999999	-1.3106694867841022	-2.4092224750183422	6.6898492252342496	0.2738636015822436	0.1096435754559368	0.2738636015822436	
+0.5300000000000000	-1.3133106897769937	-2.4113266477232269	6.6869831595268607	0.2738624964776222	0.1096435047080945	0.2738624964776222	
+0.5309999999999999	-1.3159510456836792	-2.4134158105835422	6.6841302861566083	0.2738613892874186	0.1096434338266549	0.2738613892874186	
+0.5320000000000000	-1.3185905436847787	-2.4154899367893017	6.6812906062968000	0.2738602800116413	0.1096433628116181	0.2738602800116413	
+0.5329999999999999	-1.3212291729462444	-2.4175489995929906	6.6784641210523041	0.2738591686502986	0.1096432916629842	0.2738591686502986	
+0.5340000000000000	-1.3238669226194222	-2.4195929723097240	6.6756508314595564	0.2738580552033992	0.1096432203807532	0.2738580552033992	
+0.5349999999999999	-1.3265037818411072	-2.4216218283174009	6.6728507384866020	0.2738569396709514	0.1096431489649254	0.2738569396709514	
+0.5360000000000000	-1.3291397397336100	-2.4236355410568549	6.6700638430331241	0.2738558220529637	0.1096430774155006	0.2738558220529637	
+0.5369999999999999	-1.3317747854048112	-2.4256340840320032	6.6672901459304938	0.2738547023494447	0.1096430057324791	0.2738547023494447	
+0.5380000000000000	-1.3344089079482244	-2.4276174308100043	6.6645296479417748	0.2738535805604029	0.1096429339158610	0.2738535805604029	
+0.5389999999999999	-1.3370420964430545	-2.4295855550214025	6.6617823497617934	0.2738524566858467	0.1096428619656462	0.2738524566858467	
+0.5400000000000000	-1.3396743399542619	-2.4315384303602867	6.6590482520171435	0.2738513307257849	0.1096427898818350	0.2738513307257849	
+0.5409999999999999	-1.3423056275326180	-2.4334760305844352	6.6563273552662281	0.2738502026802259	0.1096427176644273	0.2738502026802259	
+0.5420000000000000	-1.3449359482147714	-2.4353983295154693	6.6536196599993174	0.2738490725491785	0.1096426453134233	0.2738490725491785	
+0.5429999999999999	-1.3475652910233038	-2.4373053010389993	6.6509251666385572	0.2738479403326509	0.1096425728288230	0.2738479403326509	
+0.5440000000000000	-1.3501936449667933	-2.4391969191047842	6.6482438755380073	0.2738468060306521	0.1096425002106267	0.2738468060306521	
+0.5449999999999999	-1.3528209990398767	-2.4410731577268692	6.6455757869836996	0.2738456696431907	0.1096424274588342	0.2738456696431907	
+0.5460000000000000	-1.3554473422233093	-2.4429339909837440	6.6429209011936523	0.2738445311702752	0.1096423545734458	0.2738445311702752	
+0.5469999999999999	-1.3580726634840248	-2.4447793930184867	6.6402792183179145	0.2738433906119144	0.1096422815544615	0.2738433906119144	
+0.5480000000000000	-1.3606969517752039	-2.4466093380389173	6.6376507384386123	0.2738422479681167	0.1096422084018814	0.2738422479681167	
+0.5489999999999999	-1.3633201960363244	-2.4484238003177379	6.6350354615699754	0.2738411032388912	0.1096421351157055	0.2738411032388912	
+0.5500000000000000	-1.3659423851932337	-2.4502227541926933	6.6324333876583754	0.2738399564242465	0.1096420616959341	0.2738399564242465	
+0.5509999999999999	-1.3685635081582062	-2.4520061740667054	6.6298445165823718	0.2738388075241912	0.1096419881425671	0.2738388075241912	
+0.5520000000000000	-1.3711835538300061	-2.4537740344080330	6.6272688481527497	0.2738376565387341	0.1096419144556048	0.2738376565387341	
+0.5529999999999999	-1.3738025110939476	-2.4555263097504070	6.6247063821125494	0.2738365034678841	0.1096418406350470	0.2738365034678841	
+0.5540000000000000	-1.3764203688219623	-2.4572629746931893	6.6221571181371175	0.2738353483116497	0.1096417666808940	0.2738353483116497	
+0.5549999999999999	-1.3790371158726564	-2.4589840039015094	6.6196210558341404	0.2738341910700400	0.1096416925931458	0.2738341910700400	
+0.5560000000000000	-1.3816527410913779	-2.4606893721064180	6.6170981947436864	0.2738330317430637	0.1096416183718026	0.2738330317430637	
+0.5569999999999999	-1.3842672333102759	-2.4623790541050248	6.6145885343382478	0.2738318703307295	0.1096415440168643	0.2738318703307295	
+0.5580000000000001	-1.3868805813483651	-2.4640530247606574	6.6120920740227724	0.2738307068330464	0.1096414695283312	0.2738307068330464	
+0.5589999999999999	-1.3894927740115897	-2.4657112590029886	6.6096088131347255	0.2738295412500232	0.1096413949062033	0.2738295412500232	
+0.5600000000000001	-1.3921038000928845	-2.4673537318281991	6.6071387509441042	0.2738283735816689	0.1096413201504806	0.2738283735816689	
+0.5609999999999999	-1.3947136483722415	-2.4689804182991089	6.6046818866534984	0.2738272038279922	0.1096412452611634	0.2738272038279922	
+0.5620000000000001	-1.3973223076167707	-2.4705912935453349	6.6022382193981350	0.2738260319890021	0.1096411702382515	0.2738260319890021	
+0.5629999999999999	-1.3999297665807644	-2.4721863327634184	6.5998077482458992	0.2738248580647075	0.1096410950817453	0.2738248580647075	
+0.5640000000000001	-1.4025360140057617	-2.4737655112169827	6.5973904721974055	0.2738236820551174	0.1096410197916447	0.2738236820551174	
+0.5649999999999999	-1.4051410386206113	-2.4753288042368715	6.5949863901860137	0.2738225039602407	0.1096409443679498	0.2738225039602407	
+0.5660000000000001	-1.4077448291415369	-2.4768761872212899	6.5925955010778932	0.2738213237800864	0.1096408688106608	0.2738213237800864	
+0.5669999999999999	-1.4103473742722004	-2.4784076356359526	6.5902178036720560	0.2738201415146634	0.1096407931197777	0.2738201415146634	
+0.5680000000000001	-1.4129486627037664	-2.4799231250142220	6.5878532967004064	0.2738189571639809	0.1096407172953006	0.2738189571639809	
+0.5690000000000000	-1.4155486831149684	-2.4814226309572502	6.5855019788277822	0.2738177707280476	0.1096406413372296	0.2738177707280476	
+0.5700000000000001	-1.4181474241721697	-2.4829061291341250	6.5831638486519983	0.2738165822068729	0.1096405652455649	0.2738165822068729	
+0.5710000000000000	-1.4207448745294318	-2.4843735952820083	6.5808389047038975	0.2738153916004657	0.1096404890203064	0.2738153916004657	
+0.5720000000000001	-1.4233410228285779	-2.4858250052062774	6.5785271454473868	0.2738141989088350	0.1096404126614543	0.2738141989088350	
+0.5730000000000000	-1.4259358576992551	-2.4872603347806628	6.5762285692794906	0.2738130041319899	0.1096403361690087	0.2738130041319899	
+0.5740000000000001	-1.4285293677590070	-2.4886795599474016	6.5739431745304051	0.2738118072699395	0.1096402595429696	0.2738118072699395	
+0.5750000000000000	-1.4311215416133301	-2.4900826567173584	6.5716709594635194	0.2738106083226930	0.1096401827833373	0.2738106083226930	
+0.5760000000000001	-1.4337123678557444	-2.4914696011701833	6.5694119222754841	0.2738094072902595	0.1096401058901117	0.2738094072902595	
+0.5770000000000000	-1.4363018350678582	-2.4928403694544357	6.5671660610962554	0.2738082041726481	0.1096400288632930	0.2738082041726481	
+0.5780000000000001	-1.4388899318194348	-2.4941949377877384	6.5649333739891365	0.2738069989698679	0.1096399517028811	0.2738069989698679	
+0.5790000000000000	-1.4414766466684537	-2.4955332824569068	6.5627138589508274	0.2738057916819283	0.1096398744088764	0.2738057916819283	
+0.5800000000000001	-1.4440619681611815	-2.4968553798180899	6.5605075139114657	0.2738045823088383	0.1096397969812788	0.2738045823088383	
+0.5810000000000000	-1.4466458848322366	-2.4981612062969099	6.5583143367347052	0.2738033708506071	0.1096397194200884	0.2738033708506071	
+0.5820000000000001	-1.4492283852046539	-2.4994507383885987	6.5561343252177213	0.2738021573072441	0.1096396417253053	0.2738021573072441	
+0.5830000000000000	-1.4518094577899512	-2.5007239526581344	6.5539674770912875	0.2738009416787585	0.1096395638969297	0.2738009416787585	
+0.5840000000000000	-1.4543890910881994	-2.5019808257403815	6.5518137900198195	0.2737997239651593	0.1096394859349616	0.2737997239651593	
+0.5850000000000000	-1.4569672735880823	-2.5032213343402292	6.5496732616014253	0.2737985041664560	0.1096394078394011	0.2737985041664560	
+0.5860000000000000	-1.4595439937669710	-2.5044454552327218	6.5475458893679521	0.2737972822826580	0.1096393296102483	0.2737972822826580	
+0.5870000000000000	-1.4621192400909842	-2.5056531652631984	6.5454316707850415	0.2737960583137742	0.1096392512475032	0.2737960583137742	
+0.5880000000000000	-1.4646930010150592	-2.5068444413474325	6.5433306032521728	0.2737948322598144	0.1096391727511662	0.2737948322598144	
+0.5890000000000000	-1.4672652649830149	-2.5080192604717571	6.5412426841027171	0.2737936041207877	0.1096390941212370	0.2737936041207877	
+0.5900000000000000	-1.4698360204276262	-2.5091775996932171	6.5391679106040019	0.2737923738967035	0.1096390153577160	0.2737923738967035	
+0.5910000000000000	-1.4724052557706822	-2.5103194361396852	6.5371062799573334	0.2737911415875710	0.1096389364606032	0.2737911415875710	
+0.5920000000000000	-1.4749729594230614	-2.5114447470100112	6.5350577892980830	0.2737899071933998	0.1096388574298986	0.2737899071933998	
+0.5930000000000000	-1.4775391197847947	-2.5125535095741465	6.5330224356957114	0.2737886707141992	0.1096387782656024	0.2737886707141992	
+0.5940000000000000	-1.4801037252451335	-2.5136457011732829	6.5310002161538350	0.2737874321499787	0.1096386989677147	0.2737874321499787	
+0.5950000000000000	-1.4826667641826206	-2.5147212992199881	6.5289911276102828	0.2737861915007476	0.1096386195362356	0.2737861915007476	
+0.5960000000000000	-1.4852282249651538	-2.5157802811983343	6.5269951669371320	0.2737849487665155	0.1096385399711651	0.2737849487665155	
+0.5970000000000000	-1.4877880959500585	-2.5168226246640311	6.5250123309407844	0.2737837039472917	0.1096384602725034	0.2737837039472917	
+0.5980000000000000	-1.4903463654841511	-2.5178483072445617	6.5230426163619999	0.2737824570430858	0.1096383804402505	0.2737824570430858	
+0.5990000000000000	-1.4929030219038091	-2.5188573066393114	6.5210860198759626	0.2737812080539072	0.1096383004744066	0.2737812080539072	
+0.6000000000000000	-1.4954580535350437	-2.5198496006197044	6.5191425380923347	0.2737799569797655	0.1096382203749718	0.2737799569797655	
+0.6010000000000000	-1.4980114486935614	-2.5208251670293311	6.5172121675553054	0.2737787038206703	0.1096381401419461	0.2737787038206703	
+0.6020000000000000	-1.5005631956848373	-2.5217839837840783	6.5152949047436532	0.2737774485766309	0.1096380597753297	0.2737774485766309	
+0.6030000000000000	-1.5031132828041835	-2.5227260288722650	6.5133907460707938	0.2737761912476571	0.1096379792751226	0.2737761912476571	
+0.6040000000000000	-1.5056616983368163	-2.5236512803547688	6.5114996878848483	0.2737749318337583	0.1096378986413249	0.2737749318337583	
+0.6050000000000000	-1.5082084305579238	-2.5245597163651556	6.5096217264686782	0.2737736703349443	0.1096378178739368	0.2737736703349443	
+0.6060000000000000	-1.5107534677327401	-2.5254513151098159	6.5077568580399632	0.2737724067512245	0.1096377369729584	0.2737724067512245	
+0.6070000000000000	-1.5132967981166114	-2.5263260548680799	6.5059050787512520	0.2737711410826086	0.1096376559383897	0.2737711410826086	
+0.6080000000000000	-1.5158384099550650	-2.5271839139923684	6.5040663846900140	0.2737698733291062	0.1096375747702308	0.2737698733291062	
+0.6090000000000000	-1.5183782914838788	-2.5280248709082986	6.5022407718786921	0.2737686034907271	0.1096374934684819	0.2737686034907271	
+0.6100000000000000	-1.5209164309291530	-2.5288489041148283	6.5004282362747805	0.2737673315674807	0.1096374120331430	0.2737673315674807	
+0.6110000000000000	-1.5234528165073771	-2.5296559921843795	6.4986287737708608	0.2737660575593770	0.1096373304642142	0.2737660575593770	
+0.6120000000000000	-1.5259874364255035	-2.5304461137629590	6.4968423801946784	0.2737647814664255	0.1096372487616957	0.2737647814664255	
+0.6130000000000000	-1.5285202788810122	-2.5312192475702999	6.4950690513091818	0.2737635032886359	0.1096371669255876	0.2737635032886359	
+0.6140000000000000	-1.5310513320619847	-2.5319753723999741	6.4933087828126013	0.2737622230260180	0.1096370849558898	0.2737622230260180	
+0.6150000000000000	-1.5335805841471735	-2.5327144671195310	6.4915615703384990	0.2737609406785816	0.1096370028526026	0.2737609406785816	
+0.6160000000000000	-1.5361080233060727	-2.5334365106706112	6.4898274094558186	0.2737596562463364	0.1096369206157260	0.2737596562463364	
+0.6170000000000000	-1.5386336376989864	-2.5341414820690860	6.4881062956689641	0.2737583697292922	0.1096368382452602	0.2737583697292922	
+0.6180000000000000	-1.5411574154771026	-2.5348293604051726	6.4863982244178509	0.2737570811274588	0.1096367557412052	0.2737570811274588	
+0.6190000000000000	-1.5436793447825590	-2.5355001248435629	6.4847031910779638	0.2737557904408460	0.1096366731035611	0.2737557904408460	
+0.6200000000000000	-1.5461994137485200	-2.5361537546235473	6.4830211909604243	0.2737544976694637	0.1096365903323281	0.2737544976694637	
+0.6210000000000000	-1.5487176104992428	-2.5367902290591466	6.4813522193120416	0.2737532028133216	0.1096365074275062	0.2737532028133216	
+0.6220000000000000	-1.5512339231501500	-2.5374095275392214	6.4796962713153867	0.2737519058724296	0.1096364243890956	0.2737519058724296	
+0.6230000000000000	-1.5537483398079002	-2.5380116295276087	6.4780533420888453	0.2737506068467978	0.1096363412170963	0.2737506068467978	
+0.6240000000000000	-1.5562608485704610	-2.5385965145632392	6.4764234266866847	0.2737493057364358	0.1096362579115084	0.2737493057364358	
+0.6250000000000000	-1.5587714375271777	-2.5391641622602616	6.4748065200991105	0.2737480025413536	0.1096361744723321	0.2737480025413536	
+0.6260000000000000	-1.5612800947588470	-2.5397145523081655	6.4732026172523396	0.2737466972615612	0.1096360908995674	0.2737466972615612	
+0.6270000000000000	-1.5637868083377864	-2.5402476644719036	6.4716117130086461	0.2737453898970685	0.1096360071932145	0.2737453898970685	
+0.6280000000000000	-1.5662915663279073	-2.5407634785920168	6.4700338021664399	0.2737440804478854	0.1096359233532734	0.2737440804478854	
+0.6290000000000000	-1.5687943567847875	-2.5412619745847440	6.4684688794603318	0.2737427689140219	0.1096358393797443	0.2737427689140219	
+0.6300000000000000	-1.5712951677557410	-2.5417431324421607	6.4669169395611750	0.2737414552954880	0.1096357552726272	0.2737414552954880	
+0.6310000000000000	-1.5737939872798927	-2.5422069322322858	6.4653779770761641	0.2737401395922938	0.1096356710319223	0.2737401395922938	
+0.6320000000000000	-1.5762908033882472	-2.5426533540992109	6.4638519865488657	0.2737388218044492	0.1096355866576297	0.2737388218044492	
+0.6330000000000000	-1.5787856041037625	-2.5430823782632128	6.4623389624593059	0.2737375019319641	0.1096355021497494	0.2737375019319641	
+0.6340000000000000	-1.5812783774414250	-2.5434939850208775	6.4608388992240258	0.2737361799748489	0.1096354175082816	0.2737361799748489	
+0.6350000000000000	-1.5837691114083166	-2.5438881547452201	6.4593517911961502	0.2737348559331134	0.1096353327332263	0.2737348559331134	
+0.6360000000000000	-1.5862577940036928	-2.5442648678858042	6.4578776326654470	0.2737335298067678	0.1096352478245837	0.2737335298067678	
+0.6370000000000000	-1.5887444132190494	-2.5446241049688547	6.4564164178584029	0.2737322015958221	0.1096351627823539	0.2737322015958221	
+0.6380000000000000	-1.5912289570382019	-2.5449658465973855	6.4549681409382842	0.2737308713002865	0.1096350776065370	0.2737308713002865	
+0.6390000000000000	-1.5937114134373525	-2.5452900734513086	6.4535327960052022	0.2737295389201712	0.1096349922971330	0.2737295389201712	
+0.6400000000000000	-1.5961917703851665	-2.5455967662875558	6.4521103770961865	0.2737282044554861	0.1096349068541422	0.2737282044554861	
+0.6410000000000000	-1.5986700158428455	-2.5458859059401959	6.4507008781852422	0.2737268679062416	0.1096348212775645	0.2737268679062416	
+0.6420000000000000	-1.6011461377641960	-2.5461574733205490	6.4493042931834221	0.2737255292724479	0.1096347355674001	0.2737255292724479	
+0.6430000000000000	-1.6036201240957095	-2.5464114494173051	6.4479206159389042	0.2737241885541149	0.1096346497236491	0.2737241885541149	
+0.6440000000000000	-1.6060919627766319	-2.5466478152966405	6.4465498402370383	0.2737228457512531	0.1096345637463116	0.2737228457512531	
+0.6450000000000000	-1.6085616417390356	-2.5468665521023315	6.4451919598004421	0.2737215008638726	0.1096344776353878	0.2737215008638726	
+0.6460000000000000	-1.6110291489078974	-2.5470676410558717	6.4438469682890398	0.2737201538919837	0.1096343913908776	0.2737201538919837	
+0.6470000000000000	-1.6134944722011686	-2.5472510634565828	6.4425148593001591	0.2737188048355966	0.1096343050127813	0.2737188048355966	
+0.6480000000000000	-1.6159575995298492	-2.5474168006817326	6.4411956263685770	0.2737174536947216	0.1096342185010989	0.2737174536947216	
+0.6490000000000000	-1.6184185187980653	-2.5475648341866504	6.4398892629666111	0.2737161004693690	0.1096341318558305	0.2737161004693690	
+0.6499999999999999	-1.6208772179031379	-2.5476951455048384	6.4385957625041650	0.2737147451595491	0.1096340450769762	0.2737147451595491	
+0.6510000000000000	-1.6233336847356619	-2.5478077162480828	6.4373151183288231	0.2737133877652722	0.1096339581645362	0.2737133877652722	
+0.6519999999999999	-1.6257879071795747	-2.5479025281065706	6.4360473237259077	0.2737120282865486	0.1096338711185106	0.2737120282865486	
+0.6530000000000000	-1.6282398731122365	-2.5479795628490010	6.4347923719185474	0.2737106667233888	0.1096337839388994	0.2737106667233888	
+0.6539999999999999	-1.6306895704044992	-2.5480388023226967	6.4335502560677540	0.2737093030758030	0.1096336966257027	0.2737093030758030	
+0.6550000000000000	-1.6331369869207872	-2.5480802284537174	6.4323209692724976	0.2737079373438017	0.1096336091789207	0.2737079373438017	
+0.6559999999999999	-1.6355821105191644	-2.5481038232469677	6.4311045045697668	0.2737065695273953	0.1096335215985535	0.2737065695273953	
+0.6570000000000000	-1.6380249290514153	-2.5481095687863125	6.4299008549346484	0.2737051996265941	0.1096334338846012	0.2737051996265941	
+0.6579999999999999	-1.6404654303631174	-2.5480974472346851	6.4287100132804023	0.2737038276414086	0.1096333460370638	0.2737038276414086	
+0.6590000000000000	-1.6429036022937158	-2.5480674408341981	6.4275319724585280	0.2737024535718493	0.1096332580559415	0.2737024535718493	
+0.6599999999999999	-1.6453394326765951	-2.5480195319062533	6.4263667252588359	0.2737010774179267	0.1096331699412345	0.2737010774179267	
+0.6610000000000000	-1.6477729093391635	-2.5479537028516486	6.4252142644095276	0.2736996991796510	0.1096330816929427	0.2736996991796510	
+0.6619999999999999	-1.6502040201029182	-2.5478699361506942	6.4240745825772647	0.2736983188570331	0.1096329933110664	0.2736983188570331	
+0.6630000000000000	-1.6526327527835249	-2.5477682143633129	6.4229476723672416	0.2736969364500832	0.1096329047956056	0.2736969364500832	
+0.6639999999999999	-1.6550590951908957	-2.5476485201291537	6.4218335263232635	0.2736955519588120	0.1096328161465604	0.2736955519588120	
+0.6650000000000000	-1.6574830351292584	-2.5475108361676968	6.4207321369278176	0.2736941653832299	0.1096327273639309	0.2736941653832299	
+0.6659999999999999	-1.6599045603972380	-2.5473551452783632	6.4196434966021503	0.2736927767233476	0.1096326384477173	0.2736927767233476	
+0.6670000000000000	-1.6623236587879280	-2.5471814303406211	6.4185675977063354	0.2736913859791756	0.1096325493979197	0.2736913859791756	
+0.6679999999999999	-1.6647403180889688	-2.5469896743140930	6.4175044325393600	0.2736899931507245	0.1096324602145381	0.2736899931507245	
+0.6690000000000000	-1.6671545260826224	-2.5467798602386607	6.4164539933391840	0.2736885982380049	0.1096323708975727	0.2736885982380049	
+0.6699999999999999	-1.6695662705458503	-2.5465519712345723	6.4154162722828421	0.2736872012410275	0.1096322814470235	0.2736872012410275	
+0.6710000000000000	-1.6719755392503850	-2.5463059905025487	6.4143912614864851	0.2736858021598028	0.1096321918628908	0.2736858021598028	
+0.6719999999999999	-1.6743823199628103	-2.5460419013238873	6.4133789530054868	0.2736844009943415	0.1096321021451745	0.2736844009943415	
+0.6730000000000000	-1.6767866004446352	-2.5457596870605665	6.4123793388344987	0.2736829977446544	0.1096320122938749	0.2736829977446544	
+0.6739999999999999	-1.6791883684523738	-2.5454593311553491	6.4113924109075464	0.2736815924107520	0.1096319223089919	0.2736815924107520	
+0.6750000000000000	-1.6815876117376147	-2.5451408171318954	6.4104181610980859	0.2736801849926452	0.1096318321905259	0.2736801849926452	
+0.6759999999999999	-1.6839843180471052	-2.5448041285948486	6.4094565812190982	0.2736787754903445	0.1096317419384767	0.2736787754903445	
+0.6770000000000000	-1.6863784751228246	-2.5444492492299577	6.4085076630231645	0.2736773639038608	0.1096316515528446	0.2736773639038608	
+0.6779999999999999	-1.6887700707020565	-2.5440761628041670	6.4075713982025277	0.2736759502332047	0.1096315610336296	0.2736759502332047	
+0.6790000000000000	-1.6911590925174751	-2.5436848531657228	6.4066477783891926	0.2736745344783871	0.1096314703808319	0.2736745344783871	
+0.6799999999999999	-1.6935455282972129	-2.5432753042442773	6.4057367951549899	0.2736731166394188	0.1096313795944516	0.2736731166394188	
+0.6810000000000000	-1.6959293657649421	-2.5428475000509883	6.4048384400116616	0.2736716967163105	0.1096312886744888	0.2736716967163105	
+0.6819999999999999	-1.6983105926399511	-2.5424014246786162	6.4039527044109379	0.2736702747090731	0.1096311976209435	0.2736702747090731	
+0.6830000000000001	-1.7006891966372213	-2.5419370623016366	6.4030795797446149	0.2736688506177172	0.1096311064338160	0.2736688506177172	
+0.6839999999999999	-1.7030651654675042	-2.5414543971763237	6.4022190573446434	0.2736674244422540	0.1096310151131063	0.2736674244422540	
+0.6850000000000001	-1.7054384868373988	-2.5409534136408687	6.4013711284831896	0.2736659961826941	0.1096309236588146	0.2736659961826941	
+0.6859999999999999	-1.7078091484494280	-2.5404340961154634	6.4005357843727353	0.2736645658390485	0.1096308320709409	0.2736645658390485	
+0.6870000000000001	-1.7101771380021189	-2.5398964291024102	6.3997130161661486	0.2736631334113281	0.1096307403494853	0.2736631334113281	
+0.6879999999999999	-1.7125424431900749	-2.5393403971862174	6.3989028149567648	0.2736616988995436	0.1096306484944480	0.2736616988995436	
+0.6890000000000001	-1.7149050517040600	-2.5387659850336957	6.3981051717784725	0.2736602623037062	0.1096305565058291	0.2736602623037062	
+0.6899999999999999	-1.7172649512310720	-2.5381731773940550	6.3973200776057872	0.2736588236238268	0.1096304643836286	0.2736588236238268	
+0.6910000000000001	-1.7196221294544207	-2.5375619590990097	6.3965475233539371	0.2736573828599161	0.1096303721278468	0.2736573828599161	
+0.6919999999999999	-1.7219765740538058	-2.5369323150628666	6.3957874998789439	0.2736559400119853	0.1096302797384837	0.2736559400119853	
+0.6930000000000001	-1.7243282727053990	-2.5362842302826296	6.3950399979777099	0.2736544950800455	0.1096301872155394	0.2736544950800455	
+0.6940000000000000	-1.7266772130819135	-2.5356176898380891	6.3943050083880930	0.2736530480641075	0.1096300945590141	0.2736530480641075	
+0.6950000000000001	-1.7290233828526906	-2.5349326788919218	6.3935825217889910	0.2736515989641822	0.1096300017689078	0.2736515989641822	
+0.6960000000000000	-1.7313667696837733	-2.5342291826897858	6.3928725288004316	0.2736501477802809	0.1096299088452207	0.2736501477802809	
+0.6970000000000001	-1.7337073612379847	-2.5335071865604162	6.3921750199836351	0.2736486945124146	0.1096298157879529	0.2736486945124146	
+0.6980000000000000	-1.7360451451750079	-2.5327666759157177	6.3914899858411349	0.2736472391605942	0.1096297225971044	0.2736472391605942	
+0.6990000000000001	-1.7383801091514650	-2.5320076362508619	6.3908174168168204	0.2736457817248311	0.1096296292726755	0.2736457817248311	
+0.7000000000000000	-1.7407122408209907	-2.5312300531443768	6.3901573032960446	0.2736443222051360	0.1096295358146661	0.2736443222051360	
+0.7010000000000001	-1.7430415278343183	-2.5304339122582444	6.3895096356057088	0.2736428606015203	0.1096294422230766	0.2736428606015203	
+0.7020000000000000	-1.7453679578393517	-2.5296191993379935	6.3888744040143326	0.2736413969139951	0.1096293484979068	0.2736413969139951	
+0.7030000000000001	-1.7476915184812480	-2.5287859002127897	6.3882515987321540	0.2736399311425715	0.1096292546391570	0.2736399311425715	
+0.7040000000000000	-1.7500121974024951	-2.5279340007955300	6.3876412099112034	0.2736384632872605	0.1096291606468274	0.2736384632872605	
+0.7050000000000001	-1.7523299822429910	-2.5270634870829323	6.3870432276453988	0.2736369933480736	0.1096290665209179	0.2736369933480736	
+0.7060000000000000	-1.7546448606401199	-2.5261743451556313	6.3864576419706189	0.2736355213250217	0.1096289722614287	0.2736355213250217	
+0.7070000000000001	-1.7569568202288384	-2.5252665611782623	6.3858844428648007	0.2736340472181162	0.1096288778683599	0.2736340472181162	
+0.7080000000000000	-1.7592658486417445	-2.5243401213995567	6.3853236202480215	0.2736325710273683	0.1096287833417117	0.2736325710273683	
+0.7090000000000001	-1.7615719335091655	-2.5233950121524344	6.3847751639825807	0.2736310927527891	0.1096286886814841	0.2736310927527891	
+0.7100000000000000	-1.7638750624592334	-2.5224312198540888	6.3842390638730944	0.2736296123943901	0.1096285938876772	0.2736296123943901	
+0.7110000000000001	-1.7661752231179642	-2.5214487310060774	6.3837153096665755	0.2736281299521824	0.1096284989602913	0.2736281299521824	
+0.7120000000000000	-1.7684724031093366	-2.5204475321944111	6.3832038910525242	0.2736266454261773	0.1096284038993264	0.2736266454261773	
+0.7130000000000000	-1.7707665900553748	-2.5194276100896431	6.3827047976630160	0.2736251588163862	0.1096283087047825	0.2736251588163862	
+0.7140000000000000	-1.7730577715762252	-2.5183889514469566	6.3822180190727860	0.2736236701228203	0.1096282133766600	0.2736236701228203	
+0.7150000000000000	-1.7753459352902370	-2.5173315431062528	6.3817435447993240	0.2736221793454910	0.1096281179149587	0.2736221793454910	
+0.7160000000000000	-1.7776310688140393	-2.5162553719922371	6.3812813643029518	0.2736206864844096	0.1096280223196789	0.2736206864844096	
+0.7170000000000000	-1.7799131597626259	-2.5151604251145074	6.3808314669869164	0.2736191915395875	0.1096279265908207	0.2736191915395875	
+0.7180000000000000	-1.7821921957494293	-2.5140466895676372	6.3803938421974840	0.2736176945110361	0.1096278307283842	0.2736176945110361	
+0.7190000000000000	-1.7844681643864073	-2.5129141525312697	6.3799684792240257	0.2736161953987669	0.1096277347323695	0.2736161953987669	
+0.7200000000000000	-1.7867410532841148	-2.5117628012701907	6.3795553672991021	0.2736146942027912	0.1096276386027767	0.2736146942027912	
+0.7210000000000000	-1.7890108500517936	-2.5105926231344275	6.3791544955985593	0.2736131909231204	0.1096275423396060	0.2736131909231204	
+0.7220000000000000	-1.7912775422974425	-2.5094036055593212	6.3787658532416129	0.2736116855597659	0.1096274459428574	0.2736116855597659	
+0.7230000000000000	-1.7935411176279037	-2.5081957360656193	6.3783894292909427	0.2736101781127395	0.1096273494125311	0.2736101781127395	
+0.7240000000000000	-1.7958015636489419	-2.5069690022595581	6.3780252127527799	0.2736086685820522	0.1096272527486273	0.2736086685820522	
+0.7250000000000000	-1.7980588679653235	-2.5057233918329427	6.3776731925770020	0.2736071569677159	0.1096271559511459	0.2736071569677159	
+0.7260000000000000	-1.8003130181808964	-2.5044588925632310	6.3773333576572107	0.2736056432697418	0.1096270590200872	0.2736056432697418	
+0.7270000000000000	-1.8025640018986748	-2.5031754923136234	6.3770056968308459	0.2736041274881417	0.1096269619554512	0.2736041274881417	
+0.7280000000000000	-1.8048118067209138	-2.5018731790331334	6.3766901988792561	0.2736026096229270	0.1096268647572381	0.2736026096229270	
+0.7290000000000000	-1.8070564202491934	-2.5005519407566785	6.3763868525277951	0.2736010896741092	0.1096267674254480	0.2736010896741092	
+0.7300000000000000	-1.8092978300844977	-2.4992117656051547	6.3760956464459211	0.2735995676417000	0.1096266699600810	0.2735995676417000	
+0.7310000000000000	-1.8115360238272968	-2.4978526417855242	6.3758165692472790	0.2735980435257110	0.1096265723611372	0.2735980435257110	
+0.7320000000000000	-1.8137709890776277	-2.4964745575908900	6.3755496094898030	0.2735965173261537	0.1096264746286167	0.2735965173261537	
+0.7330000000000000	-1.8160027134351731	-2.4950775014005790	6.3752947556757960	0.2735949890430397	0.1096263767625198	0.2735949890430397	
+0.7340000000000000	-1.8182311844993431	-2.4936614616802228	6.3750519962520329	0.2735934586763808	0.1096262787628464	0.2735934586763808	
+0.7350000000000000	-1.8204563898693586	-2.4922264269818322	6.3748213196098549	0.2735919262261886	0.1096261806295967	0.2735919262261886	
+0.7360000000000000	-1.8226783171443288	-2.4907723859438788	6.3746027140852517	0.2735903916924746	0.1096260823627708	0.2735903916924746	
+0.7370000000000000	-1.8248969539233326	-2.4892993272913753	6.3743961679589596	0.2735888550752508	0.1096259839623689	0.2735888550752508	
+0.7380000000000000	-1.8271122878055048	-2.4878072398359503	6.3742016694565677	0.2735873163745285	0.1096258854283910	0.2735873163745285	
+0.7390000000000000	-1.8293243063901075	-2.4862961124759280	6.3740192067485868	0.2735857755903198	0.1096257867608374	0.2735857755903198	
+0.7400000000000000	-1.8315329972766217	-2.4847659341964001	6.3738487679505695	0.2735842327226363	0.1096256879597080	0.2735842327226363	
+0.7410000000000000	-1.8337383480648217	-2.4832166940693114	6.3736903411231900	0.2735826877714896	0.1096255890250031	0.2735826877714896	
+0.7420000000000000	-1.8359403463548603	-2.4816483812535273	6.3735439142723394	0.2735811407368917	0.1096254899567227	0.2735811407368917	
+0.7430000000000000	-1.8381389797473471	-2.4800609849949122	6.3734094753492236	0.2735795916188542	0.1096253907548669	0.2735795916188542	
+0.7440000000000000	-1.8403342358434323	-2.4784544946264115	6.3732870122504641	0.2735780404173890	0.1096252914194359	0.2735780404173890	
+0.7450000000000000	-1.8425261022448871	-2.4768288995681145	6.3731765128181763	0.2735764871325079	0.1096251919504299	0.2735764871325079	
+0.7460000000000000	-1.8447145665541860	-2.4751841893273365	6.3730779648400864	0.2735749317642227	0.1096250923478489	0.2735749317642227	
+0.7470000000000000	-1.8468996163745881	-2.4735203534986914	6.3729913560496154	0.2735733743125452	0.1096249926116930	0.2735733743125452	
+0.7480000000000000	-1.8490812393102170	-2.4718373817641677	6.3729166741259693	0.2735718147774873	0.1096248927419624	0.2735718147774873	
+0.7490000000000000	-1.8512594229661468	-2.4701352638931935	6.3728539066942504	0.2735702531590610	0.1096247927386572	0.2735702531590610	
+0.7500000000000000	-1.8534341549484796	-2.4684139897427197	6.3728030413255539	0.2735686894572780	0.1096246926017775	0.2735686894572780	
+0.7510000000000000	-1.8556054228644299	-2.4666735492572855	6.3727640655370363	0.2735671236721504	0.1096245923313234	0.2735671236721504	
+0.7520000000000000	-1.8577732143224048	-2.4649139324690892	6.3727369667920577	0.2735655558036899	0.1096244919272951	0.2735655558036899	
+0.7530000000000000	-1.8599375169320884	-2.4631351294980677	6.3727217325002377	0.2735639858519086	0.1096243913896927	0.2735639858519086	
+0.7540000000000000	-1.8620983183045210	-2.4613371305519558	6.3727183500175810	0.2735624138168184	0.1096242907185163	0.2735624138168184	
+0.7550000000000000	-1.8642556060521804	-2.4595199259263678	6.3727268066465577	0.2735608396984313	0.1096241899137660	0.2735608396984313	
+0.7560000000000000	-1.8664093677890707	-2.4576835060048601	6.3727470896362117	0.2735592634967593	0.1096240889754420	0.2735592634967593	
+0.7570000000000000	-1.8685595911307966	-2.4558278612590030	6.3727791861822567	0.2735576852118143	0.1096239879035443	0.2735576852118143	
+0.7580000000000000	-1.8707062636946490	-2.4539529822484534	6.3728230834271731	0.2735561048436085	0.1096238866980731	0.2735561048436085	
+0.7590000000000000	-1.8728493730996874	-2.4520588596210140	6.3728787684603070	0.2735545223921537	0.1096237853590285	0.2735545223921537	
+0.7600000000000000	-1.8749889069668222	-2.4501454841127153	6.3729462283179661	0.2735529378574622	0.1096236838864107	0.2735529378574622	
+0.7610000000000000	-1.8771248529188966	-2.4482128465478721	6.3730254499835279	0.2735513512395459	0.1096235822802198	0.2735513512395459	
+0.7620000000000000	-1.8792571985807682	-2.4462609378391549	6.3731164203875323	0.2735497625384170	0.1096234805404558	0.2735497625384170	
+0.7630000000000000	-1.8813859315793928	-2.4442897489876576	6.3732191264077791	0.2735481717540874	0.1096233786671190	0.2735481717540874	
+0.7640000000000000	-1.8835110395439068	-2.4422992710829621	6.3733335548694319	0.2735465788865694	0.1096232766602094	0.2735465788865694	
+0.7650000000000000	-1.8856325101057092	-2.4402894953032073	6.3734596925451257	0.2735449839358751	0.1096231745197271	0.2735449839358751	
+0.7660000000000000	-1.8877503308985442	-2.4382604129151528	6.3735975261550450	0.2735433869020166	0.1096230722456723	0.2735433869020166	
+0.7670000000000000	-1.8898644895585845	-2.4362120152742426	6.3737470423670537	0.2735417877850062	0.1096229698380452	0.2735417877850062	
+0.7680000000000000	-1.8919749737245137	-2.4341442938246738	6.3739082277967682	0.2735401865848558	0.1096228672968457	0.2735401865848558	
+0.7690000000000000	-1.8940817710376070	-2.4320572400994571	6.3740810690076790	0.2735385833015778	0.1096227646220742	0.2735385833015778	
+0.7700000000000000	-1.8961848691418171	-2.4299508457204810	6.3742655525112397	0.2735369779351844	0.1096226618137306	0.2735369779351844	
+0.7710000000000000	-1.8982842556838562	-2.4278251023985820	6.3744616647669723	0.2735353704856878	0.1096225588718151	0.2735353704856878	
+0.7720000000000000	-1.9003799183132779	-2.4256800019335945	6.3746693921825743	0.2735337609531002	0.1096224557963279	0.2735337609531002	
+0.7730000000000000	-1.9024718446825610	-2.4235155362144267	6.3748887211140151	0.2735321493374338	0.1096223525872690	0.2735321493374338	
+0.7740000000000000	-1.9045600224471908	-2.4213316972191139	6.3751196378656356	0.2735305356387011	0.1096222492446386	0.2735305356387011	
+0.7750000000000000	-1.9066444392657436	-2.4191284770148833	6.3753621286902487	0.2735289198569142	0.1096221457684369	0.2735289198569142	
+0.7760000000000000	-1.9087250827999716	-2.4169058677582163	6.3756161797892652	0.2735273019920854	0.1096220421586638	0.2735273019920854	
+0.7770000000000000	-1.9108019407148795	-2.4146638616949083	6.3758817773127516	0.2735256820442272	0.1096219384153197	0.2735256820442272	
+0.7780000000000000	-1.9128750006788167	-2.4124024511601276	6.3761589073595850	0.2735240600133517	0.1096218345384045	0.2735240600133517	
+0.7790000000000000	-1.9149442503635503	-2.4101216285784735	6.3764475559775171	0.2735224358994714	0.1096217305279185	0.2735224358994714	
+0.7800000000000000	-1.9170096774443595	-2.4078213864640441	6.3767477091632934	0.2735208097025987	0.1096216263838616	0.2735208097025987	
+0.7810000000000000	-1.9190712696001082	-2.4055017174204849	6.3770593528627586	0.2735191814227458	0.1096215221062342	0.2735191814227458	
+0.7820000000000000	-1.9211290145133360	-2.4031626141410549	6.3773824729709601	0.2735175510599253	0.1096214176950363	0.2735175510599253	
+0.7830000000000000	-1.9231828998703357	-2.4008040694086805	6.3777170553322424	0.2735159186141495	0.1096213131502679	0.2735159186141495	
+0.7840000000000000	-1.9252329133612418	-2.3984260760960137	6.3780630857403589	0.2735142840854309	0.1096212084719294	0.2735142840854309	
+0.7850000000000000	-1.9272790426801114	-2.3960286271654931	6.3784205499385820	0.2735126474737820	0.1096211036600207	0.2735126474737820	
+0.7860000000000000	-1.9293212755250060	-2.3936117156693939	6.3787894336197972	0.2735110087792150	0.1096209987145421	0.2735110087792150	
+0.7870000000000000	-1.9313595995980775	-2.3911753347498887	6.3791697224266128	0.2735093680017426	0.1096208936354935	0.2735093680017426	
+0.7880000000000000	-1.9333940026056509	-2.3887194776391039	6.3795614019514666	0.2735077251413773	0.1096207884228753	0.2735077251413773	
+0.7890000000000000	-1.9354244722583074	-2.3862441376591708	6.3799644577367296	0.2735060801981316	0.1096206830766874	0.2735060801981316	
+0.7900000000000000	-1.9374509962709690	-2.3837493082222863	6.3803788752748085	0.2735044331720179	0.1096205775969300	0.2735044331720179	
+0.7910000000000000	-1.9394735623629802	-2.3812349828307613	6.3808046400082592	0.2735027840630488	0.1096204719836033	0.2735027840630488	
+0.7920000000000000	-1.9414921582581948	-2.3787011550770796	6.3812417373298906	0.2735011328712371	0.1096203662367074	0.2735011328712371	
+0.7929999999999999	-1.9435067716850543	-2.3761478186439486	6.3816901525828591	0.2734994795965949	0.1096202603562424	0.2734994795965949	
+0.7940000000000000	-1.9455173903766769	-2.3735749673043527	6.3821498710607951	0.2734978242391352	0.1096201543422084	0.2734978242391352	
+0.7949999999999999	-1.9475240020709383	-2.3709825949216086	6.3826208780078897	0.2734961667988705	0.1096200481946056	0.2734961667988705	
+0.7960000000000000	-1.9495265945105573	-2.3683706954494106	6.3831031586190221	0.2734945072758134	0.1096199419134341	0.2734945072758134	
+0.7969999999999999	-1.9515251554431767	-2.3657392629318927	6.3835966980398471	0.2734928456699764	0.1096198354986940	0.2734928456699764	
+0.7980000000000000	-1.9535196726214505	-2.3630882915036704	6.3841014813669146	0.2734911819813723	0.1096197289503855	0.2734911819813723	
+0.7989999999999999	-1.9555101338031240	-2.3604177753898985	6.3846174936477720	0.2734895162100138	0.1096196222685086	0.2734895162100138	
+0.8000000000000000	-1.9574965267511217	-2.3577277089063156	6.3851447198810751	0.2734878483559135	0.1096195154530636	0.2734878483559135	
+0.8009999999999999	-1.9594788392336286	-2.3550180864592978	6.3856831450166940	0.2734861784190842	0.1096194085040505	0.2734861784190842	
+0.8020000000000000	-1.9614570590241749	-2.3522889025459071	6.3862327539558237	0.2734845063995384	0.1096193014214694	0.2734845063995384	
+0.8029999999999999	-1.9634311739017178	-2.3495401517539389	6.3867935315510866	0.2734828322972891	0.1096191942053206	0.2734828322972891	
+0.8040000000000000	-1.9654011716507305	-2.3467718287619741	6.3873654626066489	0.2734811561123490	0.1096190868556041	0.2734811561123490	
+0.8049999999999999	-1.9673670400612810	-2.3439839283394237	6.3879485318783225	0.2734794778447307	0.1096189793723201	0.2734794778447307	
+0.8060000000000000	-1.9693287669291184	-2.3411764453465791	6.3885427240736785	0.2734777974944471	0.1096188717554687	0.2734777974944471	
+0.8069999999999999	-1.9712863400557570	-2.3383493747346584	6.3891480238521527	0.2734761150615109	0.1096187640050500	0.2734761150615109	
+0.8080000000000001	-1.9732397472485594	-2.3355027115458475	6.3897644158251570	0.2734744305459351	0.1096186561210642	0.2734744305459351	
+0.8089999999999999	-1.9751889763208215	-2.3326364509133590	6.3903918845561885	0.2734727439477324	0.1096185481035114	0.2734727439477324	
+0.8100000000000001	-1.9771340150918579	-2.3297505880614646	6.3910304145609462	0.2734710552669156	0.1096184399523916	0.2734710552669156	
+0.8109999999999999	-1.9790748513870824	-2.3268451183055525	6.3916799903074253	0.2734693645034976	0.1096183316677052	0.2734693645034976	
+0.8120000000000001	-1.9810114730380952	-2.3239200370521553	6.3923405962160409	0.2734676716574914	0.1096182232494521	0.2734676716574914	
+0.8129999999999999	-1.9829438678827649	-2.3209753397990180	6.3930122166597325	0.2734659767289098	0.1096181146976326	0.2734659767289098	
+0.8140000000000001	-1.9848720237653170	-2.3180110221351202	6.3936948359640784	0.2734642797177655	0.1096180060122467	0.2734642797177655	
+0.8149999999999999	-1.9867959285364103	-2.3150270797407337	6.3943884384073977	0.2734625806240717	0.1096178971932945	0.2734625806240717	
+0.8160000000000001	-1.9887155700532302	-2.3120235083874583	6.3950930082208757	0.2734608794478414	0.1096177882407763	0.2734608794478414	
+0.8169999999999999	-1.9906309361795653	-2.3090003039382658	6.3958085295886580	0.2734591761890873	0.1096176791546922	0.2734591761890873	
+0.8180000000000001	-1.9925420147858968	-2.3059574623475405	6.3965349866479775	0.2734574708478225	0.1096175699350422	0.2734574708478225	
+0.8190000000000000	-1.9944487937494806	-2.3028949796611302	6.3972723634892557	0.2734557634240600	0.1096174605818265	0.2734557634240600	
+0.8200000000000001	-1.9963512609544314	-2.2998128520163728	6.3980206441562206	0.2734540539178127	0.1096173510950453	0.2734540539178127	
+0.8210000000000000	-1.9982494042918089	-2.2967110756421527	6.3987798126460085	0.2734523423290938	0.1096172414746987	0.2734523423290938	
+0.8220000000000001	-2.0001432116596978	-2.2935896468589219	6.3995498529092902	0.2734506286579161	0.1096171317207868	0.2734506286579161	
+0.8230000000000000	-2.0020326709632985	-2.2904485620787605	6.4003307488503749	0.2734489129042930	0.1096170218333097	0.2734489129042930	
+0.8240000000000001	-2.0039177701150082	-2.2872878178054039	6.4011224843273204	0.2734471950682371	0.1096169118122676	0.2734471950682371	
+0.8250000000000000	-2.0057984970345011	-2.2841074106342800	6.4019250431520547	0.2734454751497619	0.1096168016576606	0.2734454751497619	
+0.8260000000000000	-2.0076748396488213	-2.2809073372525566	6.4027384090904800	0.2734437531488802	0.1096166913694890	0.2734437531488802	
+0.8270000000000000	-2.0095467858924598	-2.2776875944391710	6.4035625658625879	0.2734420290656053	0.1096165809477526	0.2734420290656053	
+0.8280000000000000	-2.0114143237074451	-2.2744481790648750	6.4043974971425790	0.2734403028999502	0.1096164703924518	0.2734403028999502	
+0.8290000000000000	-2.0132774410434209	-2.2711890880922625	6.4052431865589643	0.2734385746519282	0.1096163597035866	0.2734385746519282	
+0.8300000000000000	-2.0151361258577358	-2.2679103185758156	6.4060996176946938	0.2734368443215524	0.1096162488811573	0.2734368443215524	
+0.8310000000000000	-2.0169903661155288	-2.2646118676619391	6.4069667740872562	0.2734351119088358	0.1096161379251639	0.2734351119088358	
+0.8320000000000000	-2.0188401497898036	-2.2612937325889835	6.4078446392287960	0.2734333774137918	0.1096160268356065	0.2734333774137918	
+0.8330000000000000	-2.0206854648615309	-2.2579559106873002	6.4087331965662377	0.2734316408364336	0.1096159156124853	0.2734316408364336	
+0.8340000000000000	-2.0225262993197131	-2.2545983993792604	6.4096324295013929	0.2734299021767744	0.1096158042558004	0.2734299021767744	
+0.8350000000000000	-2.0243626411614843	-2.2512211961793014	6.4105423213910697	0.2734281614348273	0.1096156927655520	0.2734281614348273	
+0.8360000000000000	-2.0261944783921857	-2.2478242986939447	6.4114628555471960	0.2734264186106058	0.1096155811417402	0.2734264186106058	
+0.8370000000000000	-2.0280217990254537	-2.2444077046218482	6.4123940152369210	0.2734246737041230	0.1096154693843652	0.2734246737041230	
+0.8380000000000000	-2.0298445910833065	-2.2409714117538235	6.4133357836827587	0.2734229267153923	0.1096153574934270	0.2734229267153923	
+0.8390000000000000	-2.0316628425962229	-2.2375154179728773	6.4142881440626649	0.2734211776444269	0.1096152454689258	0.2734211776444269	
+0.8400000000000000	-2.0334765416032310	-2.2340397212542396	6.4152510795101882	0.2734194264912401	0.1096151333108618	0.2734194264912401	
+0.8410000000000000	-2.0352856761519926	-2.2305443196653942	6.4162245731145564	0.2734176732558454	0.1096150210192351	0.2734176732558454	
+0.8420000000000000	-2.0370902342988861	-2.2270292113661139	6.4172086079208137	0.2734159179382559	0.1096149085940458	0.2734159179382559	
+0.8430000000000000	-2.0388902041090917	-2.2234943946084895	6.4182031669299242	0.2734141605384852	0.1096147960352940	0.2734141605384852	
+0.8440000000000000	-2.0406855736566771	-2.2199398677369540	6.4192082330988960	0.2734124010565466	0.1096146833429799	0.2734124010565466	
+0.8450000000000000	-2.0424763310246816	-2.2163656291883203	6.4202237893408878	0.2734106394924535	0.1096145705171037	0.2734106394924535	
+0.8460000000000000	-2.0442624643051985	-2.2127716774918063	6.4212498185253377	0.2734088758462194	0.1096144575576654	0.2734088758462194	
+0.8470000000000000	-2.0460439615994619	-2.2091580112690656	6.4222863034780655	0.2734071101178575	0.1096143444646653	0.2734071101178575	
+0.8480000000000000	-2.0478208110179317	-2.2055246292342119	6.4233332269814021	0.2734053423073814	0.1096142312381034	0.2734053423073814	
+0.8490000000000000	-2.0495930006803760	-2.2018715301938503	6.4243905717742971	0.2734035724148046	0.1096141178779798	0.2734035724148046	
+0.8500000000000000	-2.0513605187159589	-2.1981987130471041	6.4254583205524529	0.2734018004401406	0.1096140043842948	0.2734018004401406	
+0.8510000000000000	-2.0531233532633211	-2.1945061767856400	6.4265364559684111	0.2734000263834027	0.1096138907570485	0.2734000263834027	
+0.8520000000000000	-2.0548814924706669	-2.1907939204936930	6.4276249606316993	0.2733982502446046	0.1096137769962409	0.2733982502446046	
+0.8530000000000000	-2.0566349244958513	-2.1870619433480996	6.4287238171089385	0.2733964720237598	0.1096136631018723	0.2733964720237598	
+0.8540000000000000	-2.0583836375064584	-2.1833102446183128	6.4298330079239578	0.2733946917208817	0.1096135490739428	0.2733946917208817	
+0.8550000000000000	-2.0601276196798892	-2.1795388236664350	6.4309525155579141	0.2733929093359840	0.1096134349124525	0.2733929093359840	
+0.8560000000000000	-2.0618668592034486	-2.1757476799472375	6.4320823224494061	0.2733911248690803	0.1096133206174015	0.2733911248690803	
+0.8570000000000000	-2.0636013442744261	-2.1719368130081889	6.4332224109946097	0.2733893383201841	0.1096132061887900	0.2733893383201841	
+0.8580000000000000	-2.0653310631001833	-2.1681062224894743	6.4343727635473726	0.2733875496893090	0.1096130916266182	0.2733875496893090	
+0.8590000000000000	-2.0670560038982351	-2.1642559081240211	6.4355333624193518	0.2733857589764686	0.1096129769308861	0.2733857589764686	
+0.8600000000000000	-2.0687761548963368	-2.1603858697375196	6.4367041898801141	0.2733839661816767	0.1096128621015939	0.2733839661816767	
+0.8610000000000000	-2.0704915043325709	-2.1564961072484485	6.4378852281572829	0.2733821713049468	0.1096127471387418	0.2733821713049468	
+0.8620000000000000	-2.0722020404554260	-2.1525866206680897	6.4390764594366292	0.2733803743462926	0.1096126320423299	0.2733803743462926	
+0.8630000000000000	-2.0739077515238846	-2.1486574101005567	6.4402778658622033	0.2733785753057278	0.1096125168123583	0.2733785753057278	
+0.8640000000000000	-2.0756086258075088	-2.1447084757428132	6.4414894295364533	0.2733767741832661	0.1096124014488272	0.2733767741832661	
+0.8650000000000000	-2.0773046515865219	-2.1407398178846893	6.4427111325203485	0.2733749709789212	0.1096122859517367	0.2733749709789212	
+0.8660000000000000	-2.0789958171518954	-2.1367514369089085	6.4439429568334923	0.2733731656927069	0.1096121703210869	0.2733731656927069	
+0.8670000000000000	-2.0806821108054323	-2.1327433332910974	6.4451848844542390	0.2733713583246368	0.1096120545568781	0.2733713583246368	
+0.8680000000000000	-2.0823635208598508	-2.1287155075998139	6.4464368973198312	0.2733695488747248	0.1096119386591102	0.2733695488747248	
+0.8690000000000000	-2.0840400356388726	-2.1246679604965610	6.4476989773265041	0.2733677373429846	0.1096118226277836	0.2733677373429846	
+0.8700000000000000	-2.0857116434773024	-2.1206006927358025	6.4489711063296076	0.2733659237294300	0.1096117064628983	0.2733659237294300	
+0.8710000000000000	-2.0873783327211157	-2.1165137051649836	6.4502532661437355	0.2733641080340750	0.1096115901644544	0.2733641080340750	
+0.8720000000000000	-2.0890400917275413	-2.1124069987245511	6.4515454385428344	0.2733622902569331	0.1096114737324521	0.2733622902569331	
+0.8730000000000000	-2.0906969088651488	-2.1082805744479596	6.4528476052603354	0.2733604703980185	0.1096113571668916	0.2733604703980185	
+0.8740000000000000	-2.0923487725139269	-2.1041344334616956	6.4541597479892641	0.2733586484573448	0.1096112404677730	0.2733586484573448	
+0.8750000000000000	-2.0939956710653780	-2.0999685769852938	6.4554818483823802	0.2733568244349258	0.1096111236350963	0.2733568244349258	
+0.8760000000000000	-2.0956375929225906	-2.0957830063313452	6.4568138880522721	0.2733549983307757	0.1096110066688619	0.2733549983307757	
+0.8770000000000000	-2.0972745265003345	-2.0915777229055199	6.4581558485715034	0.2733531701449082	0.1096108895690698	0.2733531701449082	
+0.8780000000000000	-2.0989064602251375	-2.0873527282065711	6.4595077114727220	0.2733513398773372	0.1096107723357201	0.2733513398773372	
+0.8790000000000000	-2.1005333825353736	-2.0831080238263602	6.4608694582487800	0.2733495075280768	0.1096106549688130	0.2733495075280768	
+0.8800000000000000	-2.1021552818813474	-2.0788436114498592	6.4622410703528619	0.2733476730971408	0.1096105374683487	0.2733476730971408	
+0.8810000000000000	-2.1037721467253752	-2.0745594928551703	6.4636225291986094	0.2733458365845433	0.1096104198343272	0.2733458365845433	
+0.8820000000000000	-2.1053839655418738	-2.0702556699135362	6.4650138161602300	0.2733439979902981	0.1096103020667488	0.2733439979902981	
+0.8830000000000000	-2.1069907268174424	-2.0659321445893526	6.4664149125726302	0.2733421573144194	0.1096101841656135	0.2733421573144194	
+0.8840000000000000	-2.1085924190509475	-2.0615889189401755	6.4678257997315427	0.2733403145569211	0.1096100661309216	0.2733403145569211	
+0.8850000000000000	-2.1101890307536055	-2.0572259951167355	6.4692464588936360	0.2733384697178173	0.1096099479626731	0.2733384697178173	
+0.8860000000000000	-2.1117805504490712	-2.0528433753629467	6.4706768712766438	0.2733366227971220	0.1096098296608682	0.2733366227971220	
+0.8870000000000000	-2.1133669666735164	-2.0484410620159221	6.4721170180594889	0.2733347737948493	0.1096097112255071	0.2733347737948493	
+0.8880000000000000	-2.1149482679757177	-2.0440190575059707	6.4735668803824034	0.2733329227110132	0.1096095926565898	0.2733329227110132	
+0.8890000000000000	-2.1165244429171421	-2.0395773643566160	6.4750264393470545	0.2733310695456280	0.1096094739541166	0.2733310695456280	
+0.8900000000000000	-2.1180954800720277	-2.0351159851846039	6.4764956760166701	0.2733292142987075	0.1096093551180875	0.2733292142987075	
+0.8910000000000000	-2.1196613680274683	-2.0306349226999045	6.4779745714161496	0.2733273569702661	0.1096092361485028	0.2733273569702661	
+0.8920000000000000	-2.1212220953834993	-2.0261341797057275	6.4794631065322097	0.2733254975603178	0.1096091170453626	0.2733254975603178	
+0.8930000000000000	-2.1227776507531826	-2.0216137590985221	6.4809612623134853	0.2733236360688769	0.1096089978086670	0.2733236360688769	
+0.8940000000000000	-2.1243280227626875	-2.0170736638679876	6.4824690196706669	0.2733217724959574	0.1096088784384161	0.2733217724959574	
+0.8950000000000000	-2.1258732000513789	-2.0125138970970782	6.4839863594766260	0.2733199068415736	0.1096087589346101	0.2733199068415736	
+0.8960000000000000	-2.1274131712718942	-2.0079344619620070	6.4855132625665277	0.2733180391057397	0.1096086392972492	0.2733180391057397	
+0.8970000000000000	-2.1289479250902388	-2.0033353617322538	6.4870497097379634	0.2733161692884698	0.1096085195263335	0.2733161692884698	
+0.8980000000000000	-2.1304774501858574	-1.9987165997705696	6.4885956817510770	0.2733142973897784	0.1096083996218632	0.2733142973897784	
+0.8990000000000000	-2.1320017352517286	-1.9940781795329787	6.4901511593286907	0.2733124234096795	0.1096082795838383	0.2733124234096795	
+0.9000000000000000	-2.1335207689944418	-1.9894201045687789	6.4917161231564151	0.2733105473481875	0.1096081594122590	0.2733105473481875	
+0.9010000000000000	-2.1350345401342836	-1.9847423785205529	6.4932905538827885	0.2733086692053166	0.1096080391071255	0.2733086692053166	
+0.9020000000000000	-2.1365430374053229	-1.9800450051241674	6.4948744321194019	0.2733067889810812	0.1096079186684380	0.2733067889810812	
+0.9030000000000000	-2.1380462495554942	-1.9753279882087713	6.4964677384410194	0.2733049066754956	0.1096077980961965	0.2733049066754956	
+0.9040000000000000	-2.1395441653466785	-1.9705913316968031	6.4980704533856972	0.2733030222885741	0.1096076773904013	0.2733030222885741	
+0.9050000000000000	-2.1410367735547915	-1.9658350396039888	6.4996825574549231	0.2733011358203311	0.1096075565510524	0.2733011358203311	
+0.9060000000000000	-2.1425240629698661	-1.9610591160393436	6.5013040311137367	0.2732992472707809	0.1096074355781500	0.2732992472707809	
+0.9070000000000000	-2.1440060223961330	-1.9562635652051719	6.5029348547908477	0.2732973566399379	0.1096073144716943	0.2732973566399379	
+0.9080000000000000	-2.1454826406521104	-1.9514483913970686	6.5045750088787671	0.2732954639278165	0.1096071932316855	0.2732954639278165	
+0.9090000000000000	-2.1469539065706802	-1.9466135990039142	6.5062244737339423	0.2732935691344311	0.1096070718581235	0.2732935691344311	
+0.9100000000000000	-2.1484198089991793	-1.9417591925078779	6.5078832296768665	0.2732916722597962	0.1096069503510087	0.2732916722597962	
+0.9110000000000000	-2.1498803367994777	-1.9368851764844184	6.5095512569922125	0.2732897733039262	0.1096068287103411	0.2732897733039262	
+0.9120000000000000	-2.1513354788480652	-1.9319915556022713	6.5112285359289661	0.2732878722668356	0.1096067069361210	0.2732878722668356	
+0.9130000000000000	-2.1527852240361343	-1.9270783346234568	6.5129150467005381	0.2732859691485388	0.1096065850283484	0.2732859691485388	
+0.9140000000000000	-2.1542295612696614	-1.9221455184032750	6.5146107694849045	0.2732840639490503	0.1096064629870234	0.2732840639490503	
+0.9150000000000000	-2.1556684794694947	-1.9171931118902945	6.5163156844247219	0.2732821566683847	0.1096063408121464	0.2732821566683847	
+0.9160000000000000	-2.1571019675714318	-1.9122211201263601	6.5180297716274636	0.2732802473065564	0.1096062185037173	0.2732802473065564	
+0.9170000000000000	-2.1585300145263107	-1.9072295482465766	6.5197530111655428	0.2732783358635801	0.1096060960617364	0.2732783358635801	
+0.9180000000000000	-2.1599526093000860	-1.9022184014793182	6.5214853830764330	0.2732764223394702	0.1096059734862037	0.2732764223394702	
+0.9190000000000000	-2.1613697408739174	-1.8971876851462044	6.5232268673628102	0.2732745067342413	0.1096058507771196	0.2732745067342413	
+0.9200000000000000	-2.1627813982442499	-1.8921374046621104	6.5249774439926682	0.2732725890479081	0.1096057279344840	0.2732725890479081	
+0.9210000000000000	-2.1641875704228979	-1.8870675655351543	6.5267370928994453	0.2732706692804850	0.1096056049582971	0.2732706692804850	
+0.9220000000000000	-2.1655882464371290	-1.8819781733666869	6.5285057939821609	0.2732687474319869	0.1096054818485592	0.2732687474319869	
+0.9230000000000000	-2.1669834153297467	-1.8768692338512909	6.5302835271055324	0.2732668235024282	0.1096053586052703	0.2732668235024282	
+0.9240000000000000	-2.1683730661591762	-1.8717407527767662	6.5320702721001247	0.2732648974918236	0.1096052352284305	0.2732648974918236	
+0.9250000000000000	-2.1697571879995432	-1.8665927360241330	6.5338660087624403	0.2732629694001879	0.1096051117180402	0.2732629694001879	
+0.9260000000000000	-2.1711357699407565	-1.8614251895676053	6.5356707168550816	0.2732610392275357	0.1096049880740993	0.2732610392275357	
+0.9270000000000000	-2.1725088010886004	-1.8562381194746007	6.5374843761068666	0.2732591069738816	0.1096048642966081	0.2732591069738816	
+0.9279999999999999	-2.1738762705648034	-1.8510315319057149	6.5393069662129530	0.2732571726392404	0.1096047403855667	0.2732571726392404	
+0.9290000000000000	-2.1752381675071328	-1.8458054331147218	6.5411384668349690	0.2732552362236269	0.1096046163409752	0.2732552362236269	
+0.9299999999999999	-2.1765944810694733	-1.8405598294485577	6.5429788576011489	0.2732532977270557	0.1096044921628338	0.2732532977270557	
+0.9310000000000000	-2.1779452004219078	-1.8352947273473137	6.5448281181064534	0.2732513571495417	0.1096043678511426	0.2732513571495417	
+0.9319999999999999	-2.1792903147508040	-1.8300101333442167	6.5466862279127023	0.2732494144910996	0.1096042434059019	0.2732494144910996	
+0.9330000000000001	-2.1806298132588982	-1.8247060540656297	6.5485531665486976	0.2732474697517441	0.1096041188271117	0.2732474697517441	
+0.9339999999999999	-2.1819636851653694	-1.8193824962310261	6.5504289135103591	0.2732455229314903	0.1096039941147722	0.2732455229314903	
+0.9350000000000001	-2.1832919197059355	-1.8140394666529867	6.5523134482608532	0.2732435740303527	0.1096038692688836	0.2732435740303527	
+0.9359999999999999	-2.1846145061329221	-1.8086769722371798	6.5542067502307173	0.2732416230483464	0.1096037442894460	0.2732416230483464	
+0.9370000000000001	-2.1859314337153570	-1.8032950199823481	6.5561087988179940	0.2732396699854860	0.1096036191764595	0.2732396699854860	
+0.9379999999999999	-2.1872426917390433	-1.7978936169802981	6.5580195733883535	0.2732377148417867	0.1096034939299244	0.2732377148417867	
+0.9390000000000001	-2.1885482695066498	-1.7924727704158818	6.5599390532752366	0.2732357576172632	0.1096033685498407	0.2732357576172632	
+0.9399999999999999	-2.1898481563377858	-1.7870324875669814	6.5618672177799588	0.2732337983119303	0.1096032430362086	0.2732337983119303	
+0.9409999999999999	-2.1911423415690909	-1.7815727758044937	6.5638040461718754	0.2732318369258031	0.1096031173890284	0.2732318369258031	
+0.9419999999999999	-2.1924308145543110	-1.7760936425923139	6.5657495176884737	0.2732298734588964	0.1096029916083000	0.2732298734588964	
+0.9429999999999999	-2.1937135646643862	-1.7705950954873177	6.5677036115355349	0.2732279079112253	0.1096028656940237	0.2732279079112253	
+0.9440000000000000	-2.1949905812875303	-1.7650771421393459	6.5696663068872461	0.2732259402828047	0.1096027396461997	0.2732259402828047	
+0.9450000000000000	-2.1962618538293102	-1.7595397902911856	6.5716375828863320	0.2732239705736495	0.1096026134648280	0.2732239705736495	
+0.9460000000000000	-2.1975273717127344	-1.7539830477785507	6.5736174186441918	0.2732219987837748	0.1096024871499089	0.2732219987837748	
+0.9470000000000000	-2.1987871243783301	-1.7484069225300658	6.5756057932410172	0.2732200249131956	0.1096023607014425	0.2732200249131956	
+0.9480000000000000	-2.2000411012842278	-1.7428114225672449	6.5776026857259406	0.2732180489619270	0.1096022341194288	0.2732180489619270	
+0.9490000000000000	-2.2012892919062432	-1.7371965560044704	6.5796080751171520	0.2732160709299839	0.1096021074038683	0.2732160709299839	
+0.9500000000000000	-2.2025316857379549	-1.7315623310489756	6.5816219404020320	0.2732140908173815	0.1096019805547608	0.2732140908173815	
+0.9510000000000000	-2.2037682722907950	-1.7259087560008219	6.5836442605372838	0.2732121086241348	0.1096018535721067	0.2732121086241348	
+0.9520000000000000	-2.2049990410941214	-1.7202358392528816	6.5856750144490626	0.2732101243502588	0.1096017264559061	0.2732101243502588	
+0.9530000000000000	-2.2062239816953073	-1.7145435892908090	6.5877141810331112	0.2732081379957688	0.1096015992061590	0.2732081379957688	
+0.9540000000000000	-2.2074430836598169	-1.7088320146930243	6.5897617391548833	0.2732061495606799	0.1096014718228657	0.2732061495606799	
+0.9550000000000000	-2.2086563365712930	-1.7031011241306926	6.5918176676496820	0.2732041590450072	0.1096013443060264	0.2732041590450072	
+0.9560000000000000	-2.2098637300316328	-1.6973509263676898	6.5938819453227868	0.2732021664487658	0.1096012166556412	0.2732021664487658	
+0.9570000000000000	-2.2110652536610735	-1.6915814302605945	6.5959545509495845	0.2732001717719709	0.1096010888717102	0.2732001717719709	
+0.9580000000000000	-2.2122608970982718	-1.6857926447586502	6.5980354632756963	0.2731981750146377	0.1096009609542336	0.2731981750146377	
+0.9590000000000000	-2.2134506500003868	-1.6799845789037509	6.6001246610171220	0.2731961761767815	0.1096008329032115	0.2731961761767815	
+0.9600000000000000	-2.2146345020431601	-1.6741572418304087	6.6022221228603630	0.2731941752584174	0.1096007047186441	0.2731941752584174	
+0.9610000000000000	-2.2158124429209991	-1.6683106427657326	6.6043278274625479	0.2731921722595607	0.1096005764005317	0.2731921722595607	
+0.9620000000000000	-2.2169844623470540	-1.6624447910294027	6.6064417534515751	0.2731901671802266	0.1096004479488742	0.2731901671802266	
+0.9630000000000000	-2.2181505500533074	-1.6565596960336388	6.6085638794262485	0.2731881600204304	0.1096003193636719	0.2731881600204304	
+0.9640000000000000	-2.2193106957906421	-1.6506553672831834	6.6106941839563831	0.2731861507801874	0.1096001906449250	0.2731861507801874	
+0.9650000000000000	-2.2204648893289365	-1.6447318143752634	6.6128326455829676	0.2731841394595130	0.1096000617926335	0.2731841394595130	
+0.9660000000000000	-2.2216131204571381	-1.6387890469995678	6.6149792428182810	0.2731821260584223	0.1095999328067977	0.2731821260584223	
+0.9670000000000000	-2.2227553789833427	-1.6328270749382190	6.6171339541460252	0.2731801105769308	0.1095998036874177	0.2731801105769308	
+0.9680000000000000	-2.2238916547348815	-1.6268459080657451	6.6192967580214610	0.2731780930150537	0.1095996744344936	0.2731780930150537	
+0.9690000000000000	-2.2250219375583966	-1.6208455563490465	6.6214676328715409	0.2731760733728065	0.1095995450480257	0.2731760733728065	
+0.9700000000000000	-2.2261462173199247	-1.6148260298473716	6.6236465570950269	0.2731740516502046	0.1095994155280141	0.2731740516502046	
+0.9710000000000000	-2.2272644839049769	-1.6087873387122800	6.6258335090626517	0.2731720278472632	0.1095992858744588	0.2731720278472632	
+0.9720000000000000	-2.2283767272186195	-1.6027294931876188	6.6280284671172263	0.2731700019639979	0.1095991560873602	0.2731700019639979	
+0.9730000000000000	-2.2294829371855531	-1.5966525036094890	6.6302314095737795	0.2731679740004242	0.1095990261667183	0.2731679740004242	
+0.9740000000000000	-2.2305831037501971	-1.5905563804062104	6.6324423147196914	0.2731659439565573	0.1095988961125334	0.2731659439565573	
+0.9750000000000000	-2.2316772168767658	-1.5844411340982929	6.6346611608148276	0.2731639118324128	0.1095987659248055	0.2731639118324128	
+0.9760000000000000	-2.2327652665493511	-1.5783067752984006	6.6368879260916778	0.2731618776280061	0.1095986356035348	0.2731618776280061	
+0.9770000000000000	-2.2338472427720029	-1.5721533147113300	6.6391225887554706	0.2731598413433528	0.1095985051487215	0.2731598413433528	
+0.9780000000000000	-2.2349231355688044	-1.5659807631339597	6.6413651269843204	0.2731578029784683	0.1095983745603658	0.2731578029784683	
+0.9790000000000000	-2.2359929349839658	-1.5597891314552252	6.6436155189293684	0.2731557625333682	0.1095982438384678	0.2731557625333682	
+0.9800000000000000	-2.2370566310818853	-1.5535784306560863	6.6458737427148833	0.2731537200080680	0.1095981129830276	0.2731537200080680	
+0.9810000000000000	-2.2381142139472439	-1.5473486718094902	6.6481397764384367	0.2731516754025833	0.1095979819940455	0.2731516754025833	
+0.9820000000000000	-2.2391656736850809	-1.5410998660803314	6.6504135981710055	0.2731496287169297	0.1095978508715215	0.2731496287169297	
+0.9830000000000000	-2.2402110004208713	-1.5348320247254232	6.6526951859571151	0.2731475799511226	0.1095977196154559	0.2731475799511226	
+0.9840000000000000	-2.2412501843006094	-1.5285451590934578	6.6549845178149791	0.2731455291051778	0.1095975882258488	0.2731455291051778	
+0.9850000000000000	-2.2422832154908861	-1.5222392806249658	6.6572815717366174	0.2731434761791108	0.1095974567027003	0.2731434761791108	
+0.9860000000000000	-2.2433100841789688	-1.5159144008522878	6.6595863256880090	0.2731414211729373	0.1095973250460107	0.2731414211729373	
+0.9870000000000000	-2.2443307805728829	-1.5095705313995285	6.6618987576092046	0.2731393640866729	0.1095971932557800	0.2731393640866729	
+0.9880000000000000	-2.2453452949014894	-1.5032076839825215	6.6642188454144824	0.2731373049203333	0.1095970613320085	0.2731373049203333	
+0.9890000000000000	-2.2463536174145635	-1.4968258704087924	6.6665465669924604	0.2731352436739342	0.1095969292746963	0.2731352436739342	
+0.9900000000000000	-2.2473557383828791	-1.4904251025775146	6.6688819002062516	0.2731331803474912	0.1095967970838436	0.2731331803474912	
+0.9910000000000000	-2.2483516480982777	-1.4840053924794772	6.6712248228935724	0.2731311149410202	0.1095966647594504	0.2731311149410202	
+0.9920000000000000	-2.2493413368737629	-1.4775667521970357	6.6735753128669018	0.2731290474545368	0.1095965323015171	0.2731290474545368	
+0.9930000000000000	-2.2503247950435625	-1.4711091939040739	6.6759333479136007	0.2731269778880567	0.1095963997100438	0.2731269778880567	
+0.9940000000000000	-2.2513020129632237	-1.4646327298659751	6.6782989057960469	0.2731249062415957	0.1095962669850305	0.2731249062415957	
+0.9950000000000000	-2.2522729810096793	-1.4581373724395612	6.6806719642517791	0.2731228325151696	0.1095961341264775	0.2731228325151696	
+0.9960000000000000	-2.2532376895813333	-1.4516231340730599	6.6830525009936155	0.2731207567087942	0.1095960011343849	0.2731207567087942	
+0.9970000000000000	-2.2541961290981387	-1.4450900273060694	6.6854404937098044	0.2731186788224854	0.1095958680087529	0.2731186788224854	
+0.9980000000000000	-2.2551482900016748	-1.4385380647694999	6.6878359200641411	0.2731165988562588	0.1095957347495817	0.2731165988562588	
+0.9990000000000000	-2.2560941627552271	-1.4319672591855417	6.6902387576961182	0.2731145168101304	0.1095956013568714	0.2731145168101304	
+1.0000000000000000	-2.2570337378438650	-1.4253776233676199	6.6926489842210515	0.2731124326841160	0.1095954678306222	0.2731124326841160	
diff --git a/src/test/data/IMU/estimation_investigation_OriginLast.m b/src/test/data/IMU/estimation_investigation_OriginLast.m
new file mode 100644
index 0000000000000000000000000000000000000000..e453223756ebefeff1bef4876ee5e4265e2feff6
--- /dev/null
+++ b/src/test/data/IMU/estimation_investigation_OriginLast.m
@@ -0,0 +1,188 @@
+clear all;
+close all;
+
+data = load('../../../../KFO_cfix3D_odom.dat'); % 5sZX, 15sAll
+
+v_p = data(:,1);
+P1 = data(:,2:4);
+Q1 = data(:,5:8);
+Ab1 = data(:,9:11);
+Wb1 = data(:,12:14);
+Cp1 = data(:, 15:17);
+Cq1 = data(:, 18:20);
+Cab1 = data(:, 21:23);
+Cwb1 = data(:, 24:26);
+P2 = data(:,27:29);
+Q2 = data(:,30:33);
+Ab2 = data(:,34:36);
+Wb2 = data(:,37:39);
+Cp2 = data(:, 40:42);
+Cq2 = data(:, 43:45);
+Cab2 = data(:, 46:48);
+Cwb2 = data(:, 49:51);
+
+RangeP1_inf = P1 - 2*Cp1;
+RangeP1_sup = P1 + 2*Cp1;
+RangeAb1_inf = Ab1 - 2*Cab1;
+RangeAb1_sup = Ab1 + 2*Cab1;
+RangeWb1_inf = Wb1 - 2*Cwb1;
+RangeWb1_sup = Wb1 + 2*Cwb1;
+RangeQ1_inf = Q1(:,1:3) - 2*Cq1;
+RangeQ1_sup = Q1(:,1:3) + 2*Cq1;
+
+RangeP2_inf = P2 - 2*Cp2;
+RangeP2_sup = P2 + 2*Cp2;
+RangeAb2_inf = Ab2 - 2*Cab2;
+RangeAb2_sup = Ab2 + 2*Cab2;
+RangeWb2_inf = Wb2 - 2*Cwb2;
+RangeWb2_sup = Wb2 + 2*Cwb2;
+
+figure('Name','Varying sigma_p (Constraint)','NumberTitle','off');
+subplot(2,2,1);
+plot(v_p, P2(:,1), 'b');
+hold on;
+plot(v_p, P2(:,2), 'g');
+plot(v_p, P2(:,3), 'r');
+plot(v_p, RangeP2_inf(:,1), '--b');
+plot(v_p, RangeP2_inf(:,2), '--g');
+plot(v_p, RangeP2_inf(:,3), '--r');
+plot(v_p, RangeP2_sup(:,1), '--b');
+plot(v_p, RangeP2_sup(:,2), '--g');
+plot(v_p, RangeP2_sup(:,3), '--r');
+xlabel('sigma of p in Odometry Constraint');
+ylabel('Estimated P (last) ');
+legend('Px', 'Py', 'Pz');
+title('last position wrt sigma_p (Constraint)');
+
+subplot(2,2,2);
+plot(v_p, Q1(:,1), 'b');
+hold on;
+plot(v_p, Q1(:,2), 'g');
+plot(v_p, Q1(:,3), 'r');
+plot(v_p, Q1(:,4), 'm');
+plot(v_p, RangeQ1_inf(:,1), '--b');
+plot(v_p, RangeQ1_inf(:,2), '--g');
+plot(v_p, RangeQ1_inf(:,3), '--r');
+plot(v_p, RangeQ1_sup(:,1), '--b');
+plot(v_p, RangeQ1_sup(:,2), '--g');
+plot(v_p, RangeQ1_sup(:,3), '--r');
+xlabel('sigma p in Odometry Constraint');
+ylabel('Quaternion estimation');
+legend('Qx', 'Qy', 'Qz', 'Qw');
+title('estimated Origin Q wrt sigma_p (Constraint)');
+
+subplot(2,2,3);
+plot(v_p, Ab1(:,1), 'b');
+hold on;
+plot(v_p, Ab1(:,2), 'g');
+plot(v_p, Ab1(:,3), 'r');
+plot(v_p, RangeAb1_inf(:,1), '--b');
+plot(v_p, RangeAb1_inf(:,2), '--g');
+plot(v_p, RangeAb1_inf(:,3), '--r');
+plot(v_p, RangeAb1_sup(:,1), '--b');
+plot(v_p, RangeAb1_sup(:,2), '--g');
+plot(v_p, RangeAb1_sup(:,3), '--r');
+xlabel('sigma of p in Odometry Constraint');
+ylabel('Estimated Ab ');
+legend('Abx', 'Aby', 'Abz');
+title('ab Origin wrt sigma_p (Constraint)');
+
+subplot(2,2,4);
+plot(v_p, Wb1(:,1), 'b');
+hold on;
+plot(v_p, Wb1(:,2), 'g');
+plot(v_p, Wb1(:,3), 'r');
+plot(v_p, RangeWb1_inf(:,1), '--b');
+plot(v_p, RangeWb1_inf(:,2), '--g');
+plot(v_p, RangeWb1_inf(:,3), '--r');
+plot(v_p, RangeWb1_sup(:,1), '--b');
+plot(v_p, RangeWb1_sup(:,2), '--g');
+plot(v_p, RangeWb1_sup(:,3), '--r');
+xlabel('sigma of p in Odometry Constraint');
+ylabel('Estimated Wb ');
+legend('Wbx', 'Wby', 'Wbz');
+title('wb Origin wrt sigma_p (Constraint)');
+
+
+% 
+% figure('Name','Varying sigma_p (Constraint)','NumberTitle','off');
+% subplot(2,4,1);
+% plot(v_p, Cab1(:,1), 'b');
+% hold on;
+% plot(v_p, Cab1(:,2), 'g');
+% plot(v_p, Cab1(:,3), 'r');
+% xlabel('sigma of p in Odometry Constraint');
+% ylabel('sigma');
+% legend('Abx', 'Aby', 'Abz');
+% title('sigma(ab) wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,5);
+% plot(v_p, Ab1(:,1), 'b');
+% hold on;
+% plot(v_p, Ab1(:,2), 'g');
+% plot(v_p, Ab1(:,3), 'r');
+% xlabel('sigma of p in Odometry Constraint');
+% ylabel('sigma');
+% legend('Abx', 'Aby', 'Abz');
+% title('estimated ab wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,2);
+% plot(v_p, Cwb1(:,1), 'b');
+% hold on;
+% plot(v_p, Cwb1(:,2), 'g');
+% plot(v_p, Cwb1(:,3), 'r');
+% xlabel('sigma of p in Odometry Constraint');
+% ylabel('sigma');
+% legend('Wbx', 'Wby', 'Wbz');
+% title('sigma(wb) wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,6);
+% plot(v_p, Wb1(:,1), 'b');
+% hold on;
+% plot(v_p, Wb1(:,2), 'g');
+% plot(v_p, Wb1(:,3), 'r');
+% xlabel('sigma of p in Odometry Constraint');
+% ylabel('sigma');
+% legend('Abx', 'Aby', 'Abz');
+% title('estimated wb wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,3);
+% plot(v_p, Cp1(:,1), 'b');
+% hold on;
+% plot(v_p, Cp1(:,2), 'g');
+% plot(v_p, Cp1(:,3), 'r');
+% xlabel('sigma of p in Odometry Constraint');
+% ylabel('sigma');
+% legend('CPx', 'CPy', 'CPz');
+% title('sigma of estimated P wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,7);
+% plot(v_p, P1(:,1), 'b');
+% hold on;
+% plot(v_p, P1(:,2), 'g');
+% plot(v_p, P1(:,3), 'r');
+% xlabel('sigma p in Odometry Constraint');
+% ylabel('position (m)');
+% legend('Px', 'Py', 'Pz');
+% title('estimated P wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,4);
+% plot(v_p, Cq1(:,1), 'b');
+% hold on;
+% plot(v_p, Cq1(:,2), 'g');
+% plot(v_p, Cq1(:,3), 'r');
+% xlabel('sigma of o in Odometry Constraint');
+% ylabel('sigma');
+% legend('CQx', 'CQy', 'CQz');
+% title('sigma of estimated Quaternion wrt sigma_p (Constraint)');
+% 
+% subplot(2,4,8);
+% plot(v_p, Q1(:,1), 'b');
+% hold on;
+% plot(v_p, Q1(:,2), 'g');
+% plot(v_p, Q1(:,3), 'r');
+% plot(v_p, Q1(:,4), 'm');
+% xlabel('sigma p in Odometry Constraint');
+% ylabel('Quaternion estimation');
+% legend('Qx', 'Qy', 'Qz', 'Qw');
+% title('estimated Q wrt sigma_p (Constraint)');
diff --git a/src/test/data/IMU/imu1Rotation.txt b/src/test/data/IMU/imu1Rotation.txt
new file mode 100644
index 0000000000000000000000000000000000000000..1549c69383b55684ab3e659a4d82e19e911c0fb5
--- /dev/null
+++ b/src/test/data/IMU/imu1Rotation.txt
@@ -0,0 +1,5001 @@
+0.000468	-0.268133	-0.409381	9.832334	0.020384	0.046631	-0.018119
+0.001464	-0.234616	-0.418958	9.820364	0.021717	0.046364	-0.017986
+0.002462	-0.280103	-0.438110	9.851487	0.021051	0.047564	-0.019452
+0.003464	-0.287285	-0.464444	9.894580	0.021583	0.047697	-0.019985
+0.004463	-0.282497	-0.414169	9.815576	0.023848	0.047697	-0.017587
+0.005457	-0.256163	-0.387835	9.798818	0.023848	0.047297	-0.018386
+0.006436	-0.234616	-0.423746	9.743755	0.025047	0.047564	-0.018786
+0.007480	-0.198706	-0.430928	9.784454	0.025314	0.046364	-0.018519
+0.008479	-0.234616	-0.433322	9.746149	0.024381	0.046897	-0.019585
+0.009414	-0.287285	-0.416563	9.750937	0.024381	0.046897	-0.019052
+0.010388	-0.210676	-0.395017	9.755725	0.024115	0.047697	-0.017587
+0.011397	-0.256163	-0.402199	9.834729	0.024781	0.048230	-0.017587
+0.012398	-0.270527	-0.416563	9.856275	0.024381	0.047963	-0.017986
+0.013400	-0.265739	-0.409381	9.794030	0.024115	0.047031	-0.018786
+0.014401	-0.244192	-0.342348	9.724603	0.025047	0.046364	-0.019585
+0.015402	-0.251375	-0.325590	9.777271	0.024914	0.046631	-0.017853
+0.016407	-0.220252	-0.409381	9.777271	0.024648	0.047031	-0.018386
+0.017431	-0.263345	-0.404593	9.679116	0.023582	0.048763	-0.017986
+0.018430	-0.203494	-0.385441	9.698268	0.024515	0.048363	-0.017720
+0.019434	-0.239404	-0.433322	9.794030	0.023982	0.047031	-0.017587
+0.020479	-0.227434	-0.395017	9.746149	0.023982	0.047297	-0.018519
+0.021482	-0.229828	-0.402199	9.758119	0.023315	0.047430	-0.018652
+0.022479	-0.227434	-0.442898	9.765301	0.022783	0.047031	-0.019452
+0.023480	-0.237010	-0.459656	9.803606	0.023182	0.046631	-0.017986
+0.024479	-0.253769	-0.378259	9.844305	0.022649	0.046764	-0.018652
+0.025425	-0.203494	-0.418958	9.777271	0.023315	0.046764	-0.020251
+0.026385	-0.241798	-0.459656	9.717420	0.023182	0.046498	-0.019452
+0.027374	-0.244192	-0.452474	9.652781	0.023848	0.046498	-0.019319
+0.028376	-0.220252	-0.390229	9.636023	0.022649	0.047164	-0.020784
+0.029377	-0.193917	-0.418958	9.612083	0.022916	0.049162	-0.019851
+0.030376	-0.270527	-0.442898	9.674328	0.023982	0.048496	-0.019052
+0.031378	-0.234616	-0.418958	9.691086	0.023982	0.046498	-0.018786
+0.032401	-0.272921	-0.411775	9.691086	0.023715	0.044899	-0.019718
+0.033439	-0.251375	-0.430928	9.674328	0.022649	0.046897	-0.019452
+0.034461	-0.282497	-0.490779	9.703056	0.020784	0.048096	-0.017587
+0.035452	-0.299255	-0.469232	9.753331	0.021717	0.048896	-0.018919
+0.036438	-0.239404	-0.387835	9.741361	0.022383	0.047697	-0.019319
+0.037537	-0.213070	-0.406987	9.707844	0.021983	0.047031	-0.018786
+0.038513	-0.268133	-0.416563	9.767695	0.022783	0.046231	-0.017986
+0.039481	-0.263345	-0.390229	9.827546	0.022383	0.045698	-0.017986
+0.040456	-0.237010	-0.387835	9.849093	0.021184	0.047297	-0.018119
+0.041477	-0.260951	-0.440504	9.750937	0.019985	0.048230	-0.017720
+0.042468	-0.256163	-0.452474	9.748543	0.020784	0.046231	-0.018119
+0.043454	-0.213070	-0.435716	9.705450	0.020651	0.047430	-0.019851
+0.044439	-0.177159	-0.445292	9.703056	0.020384	0.047697	-0.019185
+0.045453	-0.215464	-0.447686	9.667146	0.021583	0.046098	-0.018919
+0.046457	-0.215464	-0.435716	9.647993	0.022783	0.046231	-0.018919
+0.047427	-0.244192	-0.418958	9.681510	0.021717	0.046764	-0.018253
+0.048451	-0.210676	-0.462050	9.688692	0.020251	0.047164	-0.018119
+0.049452	-0.258557	-0.402199	9.693480	0.019718	0.047830	-0.019185
+0.050452	-0.227434	-0.421352	9.679116	0.020784	0.047830	-0.020518
+0.051452	-0.220252	-0.454868	9.691086	0.022383	0.048230	-0.020784
+0.052452	-0.150825	-0.433322	9.743755	0.022383	0.047963	-0.018919
+0.053480	-0.239404	-0.435716	9.703056	0.021583	0.047430	-0.019452
+0.054418	-0.244192	-0.397411	9.700662	0.021717	0.046631	-0.020917
+0.055433	-0.253769	-0.430928	9.789242	0.021184	0.047430	-0.019185
+0.056476	-0.272921	-0.440504	9.806000	0.020251	0.048363	-0.019985
+0.057478	-0.258557	-0.459656	9.729391	0.019585	0.049429	-0.019319
+0.058451	-0.210676	-0.390229	9.789242	0.019985	0.049429	-0.020784
+0.059478	-0.222646	-0.406987	9.829940	0.019452	0.047963	-0.022783
+0.060476	-0.227434	-0.397411	9.717420	0.020518	0.045698	-0.022383
+0.061477	-0.191523	-0.383047	9.686298	0.021450	0.045832	-0.018519
+0.062430	-0.234616	-0.423746	9.726997	0.020651	0.045965	-0.017187
+0.063401	-0.260951	-0.423746	9.686298	0.020251	0.048096	-0.019185
+0.064398	-0.258557	-0.430928	9.755725	0.020118	0.046364	-0.020384
+0.065380	-0.246586	-0.433322	9.827546	0.020784	0.045565	-0.020384
+0.066441	-0.256163	-0.399805	9.853881	0.020384	0.047564	-0.020251
+0.067432	-0.232222	-0.368683	9.851487	0.021450	0.048496	-0.017853
+0.068424	-0.239404	-0.356712	9.734179	0.022116	0.048629	-0.017986
+0.069478	-0.208282	-0.416563	9.738967	0.022783	0.049828	-0.017853
+0.070473	-0.213070	-0.423746	9.789242	0.023049	0.050095	-0.017453
+0.071477	-0.227434	-0.385441	9.786848	0.022383	0.049162	-0.020118
+0.072474	-0.241798	-0.428534	9.715026	0.023182	0.049296	-0.019718
+0.073477	-0.263345	-0.438110	9.770089	0.022783	0.049429	-0.017986
+0.074472	-0.229828	-0.399805	9.806000	0.021583	0.048230	-0.018652
+0.075459	-0.253769	-0.409381	9.810788	0.022116	0.047564	-0.016654
+0.076430	-0.225040	-0.414169	9.808394	0.022383	0.046764	-0.017720
+0.077477	-0.294467	-0.447686	9.782060	0.022383	0.047031	-0.018253
+0.078434	-0.272921	-0.416563	9.789242	0.022116	0.048363	-0.018386
+0.079418	-0.268133	-0.459656	9.724603	0.022916	0.049695	-0.017986
+0.080409	-0.244192	-0.457262	9.813182	0.022516	0.050228	-0.017986
+0.081398	-0.241798	-0.442898	9.762907	0.023315	0.049695	-0.017453
+0.082414	-0.146037	-0.457262	9.784454	0.023449	0.048230	-0.019851
+0.083471	-0.189129	-0.440504	9.856275	0.023049	0.048896	-0.019851
+0.084477	-0.160401	-0.459656	9.829940	0.023715	0.049296	-0.019452
+0.085476	-0.229828	-0.488385	9.841911	0.024381	0.047697	-0.018519
+0.086429	-0.253769	-0.512325	9.798818	0.024115	0.047564	-0.018786
+0.087426	-0.256163	-0.505143	9.734179	0.023982	0.048230	-0.017587
+0.088426	-0.174765	-0.497961	9.731785	0.024381	0.049029	-0.018386
+0.089480	-0.205888	-0.464444	9.880215	0.024515	0.049029	-0.017986
+0.090537	-0.227434	-0.464444	9.791636	0.025314	0.048363	-0.018519
+0.091537	-0.227434	-0.464444	9.894580	0.024914	0.048496	-0.021051
+0.092536	-0.198706	-0.442898	9.966401	0.025181	0.048096	-0.020917
+0.093539	-0.222646	-0.464444	9.813182	0.025714	0.049296	-0.019985
+0.094537	-0.227434	-0.481203	9.815576	0.025714	0.049029	-0.018386
+0.095457	-0.208282	-0.464444	9.832334	0.025447	0.050361	-0.019985
+0.096482	-0.169977	-0.497961	9.808394	0.025181	0.051028	-0.020518
+0.097455	-0.179553	-0.471626	9.908944	0.024781	0.049828	-0.020118
+0.098442	-0.217858	-0.442898	9.923308	0.024914	0.049562	-0.019718
+0.099445	-0.282497	-0.428534	9.885003	0.026247	0.050228	-0.020118
+0.100436	-0.220252	-0.430928	9.827546	0.027446	0.050361	-0.021850
+0.101381	-0.225040	-0.438110	9.789242	0.027446	0.049562	-0.019851
+0.102471	-0.217858	-0.507537	9.801212	0.026913	0.049296	-0.021850
+0.103475	-0.227434	-0.466838	9.851487	0.026247	0.049962	-0.022250
+0.104477	-0.260951	-0.490779	9.808394	0.026247	0.050495	-0.019851
+0.105477	-0.270527	-0.447686	9.856275	0.025714	0.051161	-0.020384
+0.106461	-0.246586	-0.414169	9.803606	0.026513	0.049695	-0.020518
+0.107493	-0.263345	-0.452474	9.815576	0.026646	0.049828	-0.020917
+0.108448	-0.268133	-0.474021	9.801212	0.027179	0.050095	-0.020651
+0.109477	-0.229828	-0.442898	9.748543	0.026247	0.050361	-0.019452
+0.110476	-0.220252	-0.459656	9.779666	0.026779	0.050761	-0.019452
+0.111477	-0.162795	-0.399805	9.784454	0.028245	0.051294	-0.019851
+0.112476	-0.237010	-0.390229	9.726997	0.027579	0.051560	-0.019851
+0.113475	-0.241798	-0.442898	9.750937	0.026779	0.051427	-0.019718
+0.114445	-0.227434	-0.452474	9.784454	0.026247	0.050628	-0.020251
+0.115440	-0.210676	-0.440504	9.813182	0.027446	0.051427	-0.021317
+0.116442	-0.193917	-0.435716	9.829940	0.028645	0.052360	-0.021450
+0.117446	-0.193917	-0.454868	9.743755	0.029844	0.050894	-0.021450
+0.118442	-0.239404	-0.430928	9.806000	0.027979	0.047830	-0.020784
+0.119438	-0.234616	-0.488385	9.817970	0.027312	0.048496	-0.020384
+0.120442	-0.253769	-0.466838	9.724603	0.026247	0.049962	-0.021317
+0.121536	-0.263345	-0.457262	9.734179	0.026113	0.051028	-0.019452
+0.122536	-0.256163	-0.423746	9.729391	0.026646	0.050495	-0.018253
+0.123540	-0.232222	-0.433322	9.760513	0.027446	0.049296	-0.019718
+0.124474	-0.237010	-0.450080	9.825152	0.026513	0.048896	-0.020251
+0.125475	-0.237010	-0.404593	9.798818	0.028378	0.049828	-0.017453
+0.126464	-0.239404	-0.411775	9.753331	0.029844	0.050095	-0.018119
+0.127443	-0.287285	-0.406987	9.722208	0.029178	0.050495	-0.020118
+0.128499	-0.287285	-0.488385	9.813182	0.029844	0.051028	-0.021450
+0.129545	-0.227434	-0.383047	9.746149	0.030110	0.051427	-0.020251
+0.130457	-0.263345	-0.406987	9.695874	0.030776	0.050228	-0.020518
+0.131449	-0.325590	-0.399805	9.705450	0.030243	0.050361	-0.017986
+0.132440	-0.251375	-0.387835	9.715026	0.029577	0.050228	-0.018119
+0.133408	-0.294467	-0.359106	9.760513	0.029844	0.051427	-0.020651
+0.134403	-0.268133	-0.378259	9.722208	0.029844	0.050894	-0.020784
+0.135393	-0.258557	-0.428534	9.784454	0.031176	0.049695	-0.019452
+0.136430	-0.260951	-0.442898	9.741361	0.030910	0.048896	-0.019319
+0.137473	-0.277709	-0.390229	9.746149	0.029844	0.050361	-0.018919
+0.138443	-0.268133	-0.414169	9.731785	0.027979	0.050495	-0.016920
+0.139493	-0.203494	-0.430928	9.693480	0.027579	0.050361	-0.019585
+0.140500	-0.208282	-0.464444	9.791636	0.027845	0.050228	-0.019452
+0.141504	-0.282497	-0.445292	9.753331	0.029444	0.049429	-0.018919
+0.142499	-0.251375	-0.418958	9.700662	0.028778	0.049162	-0.020118
+0.143498	-0.177159	-0.380653	9.712632	0.027979	0.050495	-0.019585
+0.144455	-0.234616	-0.371077	9.710238	0.027979	0.051294	-0.018386
+0.145500	-0.189129	-0.423746	9.772483	0.027446	0.052093	-0.018519
+0.146427	-0.234616	-0.385441	9.779666	0.027712	0.051560	-0.020251
+0.147404	-0.205888	-0.433322	9.765301	0.028245	0.050894	-0.020651
+0.148404	-0.186735	-0.457262	9.760513	0.027712	0.050228	-0.018786
+0.149431	-0.179553	-0.399805	9.750937	0.027312	0.050095	-0.018786
+0.150430	-0.246586	-0.438110	9.705450	0.027579	0.049695	-0.020384
+0.151434	-0.275315	-0.411775	9.703056	0.026247	0.050761	-0.020384
+0.152537	-0.263345	-0.464444	9.758119	0.026513	0.050095	-0.019718
+0.153537	-0.270527	-0.462050	9.734179	0.025580	0.048763	-0.020251
+0.154536	-0.277709	-0.395017	9.750937	0.025181	0.050628	-0.021850
+0.155536	-0.244192	-0.421352	9.777271	0.025181	0.052093	-0.019985
+0.156537	-0.191523	-0.423746	9.760513	0.025047	0.051028	-0.018652
+0.157480	-0.198706	-0.478809	9.688692	0.024248	0.050361	-0.020118
+0.158497	-0.234616	-0.442898	9.741361	0.024381	0.049562	-0.020384
+0.159537	-0.225040	-0.416563	9.798818	0.024248	0.049828	-0.020518
+0.160538	-0.160401	-0.383047	9.772483	0.023715	0.050495	-0.019985
+0.161470	-0.198706	-0.426140	9.695874	0.023582	0.050761	-0.019452
+0.162411	-0.289679	-0.447686	9.719814	0.023715	0.051427	-0.019851
+0.163455	-0.260951	-0.442898	9.753331	0.024115	0.051161	-0.021717
+0.164453	-0.172371	-0.452474	9.729391	0.024381	0.050361	-0.021717
+0.165454	-0.241798	-0.464444	9.796424	0.024115	0.049828	-0.020917
+0.166453	-0.222646	-0.445292	9.753331	0.024381	0.049828	-0.020651
+0.167454	-0.237010	-0.442898	9.770089	0.025447	0.050228	-0.020651
+0.168454	-0.210676	-0.414169	9.734179	0.025714	0.050628	-0.019851
+0.169454	-0.184341	-0.450080	9.731785	0.023982	0.050095	-0.019851
+0.170452	-0.169977	-0.440504	9.712632	0.023315	0.050228	-0.021184
+0.171452	-0.217858	-0.387835	9.719814	0.023315	0.050761	-0.020917
+0.172453	-0.282497	-0.426140	9.734179	0.023582	0.050628	-0.021051
+0.173395	-0.284891	-0.392623	9.695874	0.023715	0.049562	-0.021051
+0.174397	-0.287285	-0.466838	9.789242	0.023049	0.050228	-0.019851
+0.175397	-0.237010	-0.464444	9.736573	0.022383	0.051294	-0.019718
+0.176399	-0.213070	-0.428534	9.743755	0.023582	0.051694	-0.019452
+0.177378	-0.172371	-0.435716	9.794030	0.024115	0.050761	-0.019851
+0.178385	-0.251375	-0.454868	9.779666	0.023049	0.050361	-0.022383
+0.179386	-0.213070	-0.457262	9.703056	0.022916	0.050361	-0.020917
+0.180375	-0.268133	-0.445292	9.734179	0.021450	0.051294	-0.020917
+0.181394	-0.260951	-0.457262	9.801212	0.021850	0.051161	-0.021051
+0.182450	-0.225040	-0.445292	9.767695	0.022383	0.051161	-0.019985
+0.183476	-0.201100	-0.440504	9.779666	0.022916	0.050628	-0.019851
+0.184443	-0.167583	-0.466838	9.724603	0.022649	0.050095	-0.021317
+0.185433	-0.201100	-0.430928	9.798818	0.022916	0.051161	-0.021717
+0.186409	-0.208282	-0.409381	9.806000	0.023449	0.050361	-0.021450
+0.187429	-0.189129	-0.416563	9.789242	0.023582	0.050495	-0.021983
+0.188422	-0.246586	-0.442898	9.801212	0.023582	0.051427	-0.019718
+0.189503	-0.263345	-0.464444	9.813182	0.023182	0.050761	-0.020118
+0.190509	-0.270527	-0.385441	9.734179	0.022250	0.049962	-0.021317
+0.191499	-0.263345	-0.337560	9.729391	0.021983	0.049429	-0.019851
+0.192445	-0.251375	-0.392623	9.765301	0.021450	0.049029	-0.018519
+0.193481	-0.227434	-0.469232	9.801212	0.021450	0.048763	-0.019052
+0.194482	-0.263345	-0.426140	9.777271	0.021717	0.049162	-0.019851
+0.195502	-0.227434	-0.450080	9.765301	0.022516	0.049562	-0.021184
+0.196507	-0.220252	-0.392623	9.841911	0.022916	0.049562	-0.021850
+0.197459	-0.268133	-0.359106	9.794030	0.023182	0.049296	-0.021583
+0.198451	-0.263345	-0.411775	9.664751	0.021983	0.049562	-0.021583
+0.199451	-0.292073	-0.469232	9.686298	0.021450	0.049695	-0.021583
+0.200452	-0.268133	-0.445292	9.686298	0.022383	0.050361	-0.022516
+0.201447	-0.222646	-0.414169	9.760513	0.024914	0.051028	-0.021317
+0.202451	-0.248980	-0.418958	9.772483	0.025314	0.049429	-0.020384
+0.203419	-0.265739	-0.392623	9.724603	0.023982	0.047963	-0.021051
+0.204491	-0.251375	-0.464444	9.798818	0.023449	0.048763	-0.020917
+0.205475	-0.229828	-0.474021	9.774877	0.023315	0.050095	-0.020917
+0.206537	-0.280103	-0.457262	9.746149	0.023315	0.049695	-0.021850
+0.207477	-0.217858	-0.466838	9.746149	0.024515	0.050495	-0.021583
+0.208478	-0.237010	-0.416563	9.767695	0.023848	0.050628	-0.021051
+0.209536	-0.234616	-0.406987	9.798818	0.023982	0.051161	-0.020384
+0.210537	-0.294467	-0.418958	9.782060	0.025580	0.050495	-0.021850
+0.211539	-0.337560	-0.354318	9.825152	0.025980	0.048896	-0.021051
+0.212541	-0.275315	-0.409381	9.803606	0.024648	0.049296	-0.021717
+0.213474	-0.260951	-0.395017	9.760513	0.023715	0.049962	-0.021450
+0.214465	-0.277709	-0.447686	9.683904	0.024781	0.049828	-0.022383
+0.215459	-0.241798	-0.414169	9.707844	0.025714	0.049029	-0.021317
+0.216462	-0.217858	-0.428534	9.683904	0.025447	0.049029	-0.020118
+0.217421	-0.208282	-0.445292	9.736573	0.026113	0.048896	-0.020118
+0.218423	-0.215464	-0.411775	9.772483	0.025847	0.048496	-0.020251
+0.219467	-0.253769	-0.423746	9.712632	0.024381	0.049296	-0.020384
+0.220467	-0.251375	-0.416563	9.736573	0.023582	0.049029	-0.022383
+0.221472	-0.210676	-0.430928	9.755725	0.024648	0.048629	-0.022383
+0.222470	-0.220252	-0.378259	9.738967	0.025314	0.049562	-0.022116
+0.223472	-0.287285	-0.414169	9.758119	0.025181	0.050361	-0.020784
+0.224472	-0.234616	-0.397411	9.717420	0.023848	0.049828	-0.019319
+0.225463	-0.179553	-0.404593	9.774877	0.023449	0.049429	-0.019851
+0.226405	-0.208282	-0.378259	9.719814	0.023315	0.049562	-0.022250
+0.227498	-0.292073	-0.387835	9.707844	0.022916	0.049296	-0.022116
+0.228471	-0.237010	-0.404593	9.767695	0.024115	0.049162	-0.020651
+0.229435	-0.234616	-0.378259	9.707844	0.022783	0.047564	-0.021583
+0.230427	-0.234616	-0.375865	9.741361	0.021184	0.048096	-0.021450
+0.231422	-0.222646	-0.368683	9.758119	0.020518	0.049296	-0.021717
+0.232422	-0.248980	-0.442898	9.753331	0.020518	0.049962	-0.021184
+0.233457	-0.198706	-0.397411	9.851487	0.021983	0.049296	-0.019718
+0.234455	-0.196312	-0.430928	9.765301	0.022783	0.048629	-0.020518
+0.235452	-0.237010	-0.433322	9.808394	0.022649	0.047031	-0.020651
+0.236491	-0.260951	-0.380653	9.825152	0.022516	0.046231	-0.021317
+0.237507	-0.189129	-0.414169	9.827546	0.021317	0.047031	-0.019052
+0.238477	-0.186735	-0.409381	9.801212	0.022383	0.048763	-0.018652
+0.239479	-0.244192	-0.390229	9.715026	0.021583	0.048763	-0.019718
+0.240473	-0.237010	-0.399805	9.731785	0.021051	0.048230	-0.021184
+0.241539	-0.203494	-0.383047	9.760513	0.020384	0.048096	-0.022116
+0.242538	-0.239404	-0.359106	9.710238	0.021717	0.048363	-0.020518
+0.243536	-0.201100	-0.325590	9.762907	0.021317	0.049828	-0.020118
+0.244494	-0.253769	-0.361500	9.770089	0.020251	0.048763	-0.019052
+0.245482	-0.256163	-0.411775	9.784454	0.020651	0.049962	-0.019319
+0.246463	-0.265739	-0.442898	9.803606	0.022783	0.049162	-0.020651
+0.247453	-0.284891	-0.452474	9.681510	0.021051	0.048363	-0.020384
+0.248457	-0.272921	-0.440504	9.734179	0.019985	0.049429	-0.020384
+0.249446	-0.217858	-0.428534	9.782060	0.020251	0.049562	-0.018919
+0.250425	-0.229828	-0.414169	9.767695	0.020784	0.049029	-0.018652
+0.251399	-0.227434	-0.483597	9.746149	0.019585	0.049029	-0.020118
+0.252384	-0.241798	-0.406987	9.786848	0.019851	0.051028	-0.019052
+0.253422	-0.251375	-0.459656	9.813182	0.020917	0.051028	-0.019985
+0.254528	-0.265739	-0.433322	9.808394	0.022250	0.048896	-0.021450
+0.255529	-0.239404	-0.421352	9.822758	0.022516	0.047830	-0.019985
+0.256500	-0.248980	-0.466838	9.861063	0.021583	0.048363	-0.018519
+0.257520	-0.292073	-0.454868	9.813182	0.022383	0.049029	-0.019319
+0.258508	-0.208282	-0.507537	9.762907	0.021583	0.049828	-0.018919
+0.259528	-0.220252	-0.462050	9.758119	0.021184	0.048763	-0.019585
+0.260468	-0.215464	-0.438110	9.825152	0.020384	0.047164	-0.019718
+0.261529	-0.260951	-0.442898	9.777271	0.020518	0.048763	-0.019052
+0.262456	-0.232222	-0.399805	9.715026	0.021717	0.050894	-0.019185
+0.263429	-0.208282	-0.390229	9.832334	0.020651	0.049828	-0.019851
+0.264428	-0.258557	-0.440504	9.894580	0.021051	0.048230	-0.020518
+0.265419	-0.251375	-0.387835	9.837123	0.021583	0.049029	-0.019319
+0.266432	-0.265739	-0.423746	9.841911	0.021184	0.049296	-0.018919
+0.267432	-0.222646	-0.481203	9.810788	0.021184	0.049429	-0.018786
+0.268429	-0.210676	-0.433322	9.810788	0.021583	0.048896	-0.018652
+0.269511	-0.239404	-0.359106	9.827546	0.021850	0.049029	-0.018253
+0.270514	-0.263345	-0.428534	9.822758	0.020917	0.048896	-0.018652
+0.271512	-0.268133	-0.462050	9.810788	0.021983	0.048763	-0.019585
+0.272515	-0.263345	-0.440504	9.798818	0.022516	0.049429	-0.018919
+0.273516	-0.258557	-0.428534	9.774877	0.023582	0.049296	-0.017453
+0.274515	-0.225040	-0.442898	9.810788	0.023848	0.049429	-0.017853
+0.275513	-0.241798	-0.430928	9.837123	0.022649	0.049562	-0.019851
+0.276445	-0.251375	-0.452474	9.810788	0.022649	0.049029	-0.020118
+0.277458	-0.241798	-0.450080	9.762907	0.023049	0.049828	-0.019185
+0.278510	-0.248980	-0.466838	9.748543	0.023049	0.049695	-0.019851
+0.279513	-0.229828	-0.450080	9.774877	0.023582	0.048363	-0.018386
+0.280437	-0.244192	-0.404593	9.748543	0.024515	0.048763	-0.019718
+0.281455	-0.270527	-0.457262	9.726997	0.024381	0.049429	-0.019452
+0.282454	-0.256163	-0.464444	9.726997	0.024515	0.049162	-0.020518
+0.283454	-0.287285	-0.423746	9.834729	0.023982	0.048230	-0.019452
+0.284449	-0.268133	-0.416563	9.782060	0.024648	0.048629	-0.020251
+0.285455	-0.253769	-0.440504	9.777271	0.024914	0.049962	-0.019985
+0.286453	-0.227434	-0.442898	9.729391	0.024781	0.048763	-0.019185
+0.287549	-0.272921	-0.418958	9.741361	0.024248	0.048230	-0.021317
+0.288513	-0.213070	-0.490779	9.839517	0.023449	0.047963	-0.021583
+0.289534	-0.220252	-0.433322	9.758119	0.022916	0.047697	-0.019452
+0.290536	-0.246586	-0.397411	9.837123	0.023315	0.049695	-0.017453
+0.291536	-0.248980	-0.402199	9.832334	0.023582	0.050495	-0.017853
+0.292536	-0.229828	-0.476415	9.755725	0.023715	0.048363	-0.018786
+0.293536	-0.323196	-0.450080	9.758119	0.023582	0.047297	-0.018519
+0.294535	-0.251375	-0.466838	9.832334	0.024115	0.048230	-0.018652
+0.295536	-0.229828	-0.452474	9.832334	0.024515	0.048096	-0.018386
+0.296458	-0.263345	-0.433322	9.777271	0.024381	0.048230	-0.018386
+0.297433	-0.239404	-0.423746	9.762907	0.024381	0.048096	-0.017320
+0.298426	-0.251375	-0.378259	9.825152	0.024648	0.047697	-0.017720
+0.299431	-0.284891	-0.378259	9.858669	0.025447	0.049029	-0.019319
+0.300432	-0.287285	-0.395017	9.765301	0.025047	0.050228	-0.017187
+0.301416	-0.260951	-0.416563	9.724603	0.024648	0.050228	-0.016920
+0.302514	-0.282497	-0.411775	9.746149	0.025047	0.047830	-0.018652
+0.303515	-0.301649	-0.375865	9.832334	0.025314	0.047830	-0.019452
+0.304512	-0.284891	-0.399805	9.791636	0.025447	0.048629	-0.018786
+0.305514	-0.260951	-0.435716	9.770089	0.024648	0.048230	-0.018119
+0.306513	-0.239404	-0.442898	9.794030	0.023315	0.048496	-0.017986
+0.307473	-0.270527	-0.397411	9.846699	0.023049	0.048096	-0.018253
+0.308481	-0.239404	-0.392623	9.731785	0.022116	0.047430	-0.018519
+0.309515	-0.260951	-0.430928	9.755725	0.023182	0.048096	-0.019585
+0.310514	-0.253769	-0.399805	9.803606	0.023449	0.048230	-0.018119
+0.311512	-0.213070	-0.416563	9.755725	0.024248	0.046897	-0.016254
+0.312512	-0.215464	-0.452474	9.779666	0.023982	0.047031	-0.017054
+0.313430	-0.210676	-0.421352	9.820364	0.022916	0.046764	-0.017187
+0.314407	-0.186735	-0.404593	9.782060	0.023049	0.047164	-0.018786
+0.315435	-0.193917	-0.447686	9.760513	0.022649	0.047564	-0.017720
+0.316428	-0.287285	-0.488385	9.784454	0.024781	0.047564	-0.017587
+0.317434	-0.239404	-0.474021	9.798818	0.024381	0.047164	-0.017587
+0.318433	-0.256163	-0.423746	9.803606	0.022649	0.047963	-0.018919
+0.319433	-0.251375	-0.395017	9.750937	0.021983	0.048629	-0.018919
+0.320507	-0.237010	-0.438110	9.774877	0.023715	0.048363	-0.018386
+0.321444	-0.260951	-0.459656	9.765301	0.024248	0.047963	-0.017453
+0.322483	-0.227434	-0.483597	9.762907	0.023315	0.047830	-0.018253
+0.323514	-0.201100	-0.450080	9.767695	0.022250	0.046764	-0.019851
+0.324512	-0.210676	-0.428534	9.758119	0.022516	0.048230	-0.020251
+0.325441	-0.227434	-0.430928	9.789242	0.022516	0.048496	-0.019185
+0.326424	-0.248980	-0.447686	9.789242	0.023582	0.047830	-0.019319
+0.327411	-0.294467	-0.459656	9.782060	0.024115	0.048363	-0.018519
+0.328407	-0.198706	-0.459656	9.772483	0.023049	0.049029	-0.018519
+0.329404	-0.248980	-0.430928	9.755725	0.023582	0.048496	-0.017853
+0.330406	-0.196312	-0.435716	9.786848	0.023582	0.048230	-0.017853
+0.331405	-0.193917	-0.450080	9.703056	0.023182	0.047963	-0.019319
+0.332406	-0.225040	-0.421352	9.724603	0.023848	0.049029	-0.019585
+0.333422	-0.210676	-0.397411	9.750937	0.022649	0.047697	-0.019052
+0.334420	-0.220252	-0.454868	9.724603	0.022783	0.046897	-0.018519
+0.335424	-0.232222	-0.466838	9.726997	0.022916	0.047564	-0.018652
+0.336436	-0.260951	-0.397411	9.688692	0.022116	0.048629	-0.019452
+0.337437	-0.217858	-0.373471	9.703056	0.020784	0.050628	-0.019185
+0.338444	-0.208282	-0.438110	9.755725	0.022516	0.049695	-0.019052
+0.339420	-0.248980	-0.378259	9.741361	0.023715	0.047297	-0.018519
+0.340422	-0.277709	-0.366289	9.774877	0.024648	0.048096	-0.018652
+0.341440	-0.234616	-0.397411	9.832334	0.023582	0.048763	-0.018386
+0.342435	-0.210676	-0.445292	9.861063	0.023449	0.048496	-0.018652
+0.343438	-0.253769	-0.462050	9.767695	0.022783	0.047164	-0.018386
+0.344435	-0.270527	-0.457262	9.746149	0.022383	0.047963	-0.019851
+0.345430	-0.275315	-0.454868	9.808394	0.022383	0.049562	-0.019052
+0.346421	-0.248980	-0.435716	9.719814	0.022783	0.050628	-0.019052
+0.347420	-0.258557	-0.430928	9.760513	0.023315	0.049828	-0.016920
+0.348421	-0.237010	-0.478809	9.789242	0.023182	0.049828	-0.018919
+0.349428	-0.186735	-0.416563	9.796424	0.023182	0.048496	-0.018253
+0.350426	-0.210676	-0.445292	9.748543	0.023049	0.047564	-0.018786
+0.351428	-0.246586	-0.464444	9.758119	0.023449	0.047697	-0.018919
+0.352426	-0.227434	-0.390229	9.703056	0.024248	0.046498	-0.020384
+0.353377	-0.227434	-0.430928	9.691086	0.023982	0.047031	-0.021450
+0.354403	-0.234616	-0.404593	9.762907	0.023982	0.048896	-0.021450
+0.355372	-0.244192	-0.390229	9.729391	0.023182	0.050628	-0.021450
+0.356381	-0.227434	-0.483597	9.743755	0.023848	0.049695	-0.020518
+0.357352	-0.232222	-0.411775	9.820364	0.023182	0.049962	-0.020651
+0.358347	-0.263345	-0.411775	9.794030	0.023182	0.050095	-0.020651
+0.359358	-0.246586	-0.371077	9.750937	0.023315	0.049828	-0.019851
+0.360406	-0.270527	-0.392623	9.813182	0.022649	0.049695	-0.019851
+0.361413	-0.248980	-0.392623	9.810788	0.023315	0.048496	-0.019985
+0.362415	-0.246586	-0.351924	9.772483	0.024648	0.049029	-0.020518
+0.363389	-0.251375	-0.356712	9.770089	0.023449	0.050361	-0.021184
+0.364392	-0.272921	-0.402199	9.798818	0.021717	0.051161	-0.021051
+0.365434	-0.287285	-0.404593	9.767695	0.021717	0.049828	-0.021850
+0.366391	-0.263345	-0.459656	9.827546	0.021850	0.049562	-0.022383
+0.367409	-0.241798	-0.442898	9.791636	0.023982	0.049962	-0.021717
+0.368429	-0.253769	-0.423746	9.803606	0.024248	0.050095	-0.020651
+0.369490	-0.260951	-0.474021	9.875427	0.024115	0.050228	-0.020251
+0.370487	-0.237010	-0.416563	9.755725	0.022516	0.051161	-0.020384
+0.371483	-0.181947	-0.397411	9.738967	0.021983	0.051694	-0.022783
+0.372486	-0.270527	-0.426140	9.796424	0.021850	0.051694	-0.023582
+0.373487	-0.229828	-0.390229	9.820364	0.022649	0.049828	-0.021983
+0.374479	-0.232222	-0.409381	9.803606	0.022783	0.048896	-0.021850
+0.375460	-0.205888	-0.416563	9.791636	0.023049	0.050095	-0.021184
+0.376412	-0.241798	-0.373471	9.746149	0.024115	0.050228	-0.020784
+0.377444	-0.272921	-0.375865	9.729391	0.023715	0.051028	-0.021583
+0.378462	-0.277709	-0.361500	9.760513	0.022916	0.049296	-0.020118
+0.379459	-0.268133	-0.411775	9.817970	0.023582	0.050894	-0.020917
+0.380388	-0.256163	-0.423746	9.896974	0.025714	0.050495	-0.022916
+0.381466	-0.239404	-0.423746	9.829940	0.025314	0.049562	-0.021450
+0.382461	-0.241798	-0.445292	9.750937	0.025047	0.049029	-0.021184
+0.383464	-0.294467	-0.395017	9.750937	0.024248	0.049296	-0.021450
+0.384465	-0.268133	-0.423746	9.755725	0.024248	0.049962	-0.022383
+0.385441	-0.201100	-0.462050	9.686298	0.023582	0.051161	-0.021184
+0.386445	-0.217858	-0.471626	9.753331	0.023848	0.052093	-0.021317
+0.387444	-0.268133	-0.454868	9.796424	0.024781	0.050894	-0.023182
+0.388468	-0.227434	-0.454868	9.738967	0.023715	0.050228	-0.021850
+0.389475	-0.241798	-0.445292	9.693480	0.023315	0.050761	-0.021184
+0.390508	-0.280103	-0.430928	9.743755	0.023582	0.050628	-0.020651
+0.391510	-0.287285	-0.409381	9.808394	0.024115	0.049562	-0.020118
+0.392511	-0.222646	-0.423746	9.770089	0.024914	0.049162	-0.021717
+0.393537	-0.239404	-0.438110	9.767695	0.025847	0.049296	-0.022516
+0.394534	-0.205888	-0.375865	9.743755	0.025980	0.049429	-0.022649
+0.395509	-0.220252	-0.421352	9.717420	0.027046	0.050495	-0.023315
+0.396445	-0.260951	-0.426140	9.760513	0.025447	0.050628	-0.021717
+0.397408	-0.237010	-0.426140	9.760513	0.024515	0.048763	-0.021317
+0.398407	-0.282497	-0.430928	9.750937	0.025980	0.047031	-0.020917
+0.399407	-0.205888	-0.438110	9.782060	0.028112	0.048096	-0.020917
+0.400401	-0.191523	-0.385441	9.736573	0.028511	0.048763	-0.021317
+0.401357	-0.213070	-0.378259	9.729391	0.027179	0.049695	-0.021717
+0.402357	-0.239404	-0.445292	9.784454	0.025580	0.049962	-0.021850
+0.403378	-0.280103	-0.399805	9.798818	0.026779	0.049828	-0.019718
+0.404358	-0.241798	-0.421352	9.808394	0.029577	0.047830	-0.020384
+0.405360	-0.241798	-0.428534	9.827546	0.030377	0.048230	-0.021184
+0.406353	-0.275315	-0.411775	9.808394	0.029444	0.050095	-0.021450
+0.407359	-0.268133	-0.380653	9.767695	0.030110	0.051694	-0.020651
+0.408358	-0.210676	-0.378259	9.724603	0.030377	0.050495	-0.020917
+0.409354	-0.237010	-0.423746	9.724603	0.029311	0.048763	-0.020118
+0.410354	-0.215464	-0.421352	9.758119	0.029178	0.048629	-0.019851
+0.411353	-0.179553	-0.390229	9.789242	0.030643	0.047963	-0.019185
+0.412358	-0.239404	-0.430928	9.760513	0.030510	0.048896	-0.020917
+0.413355	-0.201100	-0.383047	9.755725	0.030643	0.047430	-0.020917
+0.414354	-0.220252	-0.438110	9.765301	0.030377	0.047164	-0.022783
+0.415356	-0.203494	-0.447686	9.703056	0.029444	0.049029	-0.023449
+0.416352	-0.232222	-0.366289	9.724603	0.030110	0.049429	-0.022250
+0.417358	-0.308832	-0.366289	9.669540	0.031176	0.049296	-0.020784
+0.418353	-0.294467	-0.351924	9.619265	0.030110	0.048096	-0.019052
+0.419353	-0.203494	-0.402199	9.726997	0.027712	0.049828	-0.018386
+0.420358	-0.227434	-0.440504	9.777271	0.026779	0.049828	-0.018919
+0.421353	-0.220252	-0.404593	9.755725	0.027845	0.048896	-0.019851
+0.422354	-0.193917	-0.404593	9.683904	0.028645	0.049162	-0.019985
+0.423353	-0.244192	-0.383047	9.707844	0.027579	0.049029	-0.021051
+0.424358	-0.270527	-0.404593	9.794030	0.026513	0.048363	-0.021583
+0.425358	-0.260951	-0.414169	9.877821	0.026113	0.048096	-0.020118
+0.426353	-0.260951	-0.387835	9.829940	0.026646	0.049162	-0.018652
+0.427355	-0.260951	-0.380653	9.782060	0.027179	0.049828	-0.018519
+0.428358	-0.215464	-0.383047	9.806000	0.027446	0.049296	-0.019851
+0.429374	-0.184341	-0.442898	9.734179	0.026380	0.049162	-0.019851
+0.430374	-0.246586	-0.397411	9.657569	0.024781	0.049562	-0.020518
+0.431463	-0.263345	-0.380653	9.619265	0.023848	0.048629	-0.020384
+0.432451	-0.246586	-0.359106	9.681510	0.023848	0.049029	-0.019052
+0.433447	-0.268133	-0.349530	9.753331	0.024648	0.049296	-0.019985
+0.434451	-0.258557	-0.392623	9.803606	0.023848	0.048496	-0.020518
+0.435450	-0.251375	-0.390229	9.820364	0.022916	0.048629	-0.019452
+0.436458	-0.229828	-0.411775	9.772483	0.021717	0.050228	-0.020384
+0.437446	-0.280103	-0.452474	9.767695	0.021583	0.049828	-0.020518
+0.438451	-0.191523	-0.452474	9.722208	0.023049	0.049296	-0.019052
+0.439451	-0.184341	-0.397411	9.705450	0.021850	0.050095	-0.019319
+0.440431	-0.217858	-0.402199	9.762907	0.021184	0.050761	-0.020917
+0.441432	-0.272921	-0.392623	9.772483	0.021051	0.050628	-0.020518
+0.442448	-0.280103	-0.392623	9.810788	0.021983	0.049429	-0.019985
+0.443451	-0.210676	-0.414169	9.729391	0.021184	0.049562	-0.019585
+0.444451	-0.256163	-0.442898	9.748543	0.020784	0.050228	-0.019985
+0.445451	-0.248980	-0.404593	9.762907	0.020518	0.051427	-0.020251
+0.446387	-0.220252	-0.402199	9.801212	0.020917	0.051028	-0.021317
+0.447358	-0.244192	-0.406987	9.803606	0.021184	0.050894	-0.021717
+0.448363	-0.225040	-0.454868	9.738967	0.020118	0.051028	-0.020384
+0.449511	-0.251375	-0.485991	9.722208	0.019585	0.049828	-0.018519
+0.450481	-0.270527	-0.447686	9.753331	0.020784	0.050361	-0.018786
+0.451467	-0.258557	-0.438110	9.722208	0.020784	0.051294	-0.020518
+0.452509	-0.246586	-0.438110	9.734179	0.020784	0.050095	-0.022383
+0.453511	-0.237010	-0.390229	9.679116	0.020651	0.048363	-0.023315
+0.454437	-0.205888	-0.402199	9.698268	0.021184	0.049029	-0.022649
+0.455513	-0.215464	-0.416563	9.753331	0.020917	0.049296	-0.022383
+0.456446	-0.260951	-0.435716	9.815576	0.020118	0.048763	-0.020917
+0.457510	-0.268133	-0.445292	9.786848	0.019851	0.049296	-0.020784
+0.458511	-0.237010	-0.416563	9.803606	0.021317	0.050495	-0.020784
+0.459480	-0.215464	-0.387835	9.827546	0.021717	0.050361	-0.022383
+0.460466	-0.189129	-0.430928	9.849093	0.021450	0.049162	-0.023982
+0.461512	-0.248980	-0.452474	9.815576	0.021583	0.050095	-0.023582
+0.462517	-0.270527	-0.385441	9.791636	0.020651	0.051161	-0.021450
+0.463418	-0.222646	-0.395017	9.806000	0.021850	0.051161	-0.021051
+0.464438	-0.208282	-0.399805	9.794030	0.023715	0.051427	-0.021850
+0.465443	-0.222646	-0.378259	9.770089	0.023715	0.051028	-0.021051
+0.466437	-0.220252	-0.416563	9.707844	0.023982	0.050095	-0.022516
+0.467421	-0.241798	-0.440504	9.722208	0.023182	0.049429	-0.023049
+0.468416	-0.280103	-0.454868	9.762907	0.022916	0.049029	-0.021717
+0.469422	-0.232222	-0.481203	9.762907	0.022916	0.049695	-0.020518
+0.470397	-0.244192	-0.481203	9.782060	0.022250	0.050761	-0.020784
+0.471383	-0.260951	-0.380653	9.719814	0.023449	0.049962	-0.022516
+0.472390	-0.225040	-0.418958	9.710238	0.024781	0.047963	-0.021983
+0.473354	-0.225040	-0.474021	9.693480	0.024648	0.048096	-0.021317
+0.474359	-0.265739	-0.442898	9.710238	0.022383	0.049029	-0.021717
+0.475358	-0.268133	-0.438110	9.717420	0.021450	0.049962	-0.023315
+0.476365	-0.225040	-0.421352	9.746149	0.021717	0.049828	-0.021583
+0.477343	-0.244192	-0.438110	9.784454	0.021717	0.049429	-0.021051
+0.478364	-0.239404	-0.430928	9.798818	0.022383	0.049962	-0.022649
+0.479364	-0.244192	-0.442898	9.870639	0.022649	0.049828	-0.023449
+0.480369	-0.277709	-0.421352	9.782060	0.020784	0.049162	-0.022250
+0.481365	-0.256163	-0.371077	9.806000	0.020784	0.049162	-0.021717
+0.482385	-0.220252	-0.414169	9.798818	0.022116	0.050495	-0.021850
+0.483406	-0.189129	-0.469232	9.791636	0.024115	0.051161	-0.022383
+0.484402	-0.244192	-0.392623	9.760513	0.022916	0.050628	-0.023315
+0.485398	-0.227434	-0.385441	9.655175	0.022383	0.049429	-0.023449
+0.486433	-0.270527	-0.378259	9.755725	0.021850	0.048096	-0.023449
+0.487411	-0.275315	-0.371077	9.815576	0.021717	0.048763	-0.022649
+0.488409	-0.251375	-0.359106	9.784454	0.022250	0.049562	-0.021850
+0.489452	-0.220252	-0.387835	9.710238	0.021983	0.049962	-0.021983
+0.490451	-0.208282	-0.387835	9.762907	0.022516	0.049429	-0.022916
+0.491451	-0.234616	-0.428534	9.746149	0.022783	0.048230	-0.023315
+0.492445	-0.284891	-0.378259	9.736573	0.023049	0.049029	-0.021717
+0.493446	-0.277709	-0.406987	9.731785	0.021317	0.050228	-0.021850
+0.494413	-0.265739	-0.368683	9.743755	0.021317	0.048896	-0.021051
+0.495393	-0.246586	-0.426140	9.770089	0.021317	0.047697	-0.020518
+0.496412	-0.270527	-0.397411	9.789242	0.021051	0.048096	-0.020518
+0.497388	-0.289679	-0.445292	9.777271	0.021051	0.049162	-0.021051
+0.498385	-0.304043	-0.390229	9.691086	0.021051	0.050095	-0.022116
+0.499385	-0.311226	-0.414169	9.686298	0.021184	0.050761	-0.022916
+0.500459	-0.292073	-0.414169	9.674328	0.021317	0.049429	-0.023049
+0.501460	-0.287285	-0.361500	9.695874	0.021051	0.049695	-0.021583
+0.502461	-0.208282	-0.395017	9.729391	0.021850	0.050628	-0.020917
+0.503460	-0.203494	-0.380653	9.770089	0.022250	0.049162	-0.021450
+0.504460	-0.225040	-0.366289	9.683904	0.022916	0.049029	-0.020518
+0.505462	-0.268133	-0.380653	9.782060	0.022250	0.049562	-0.021184
+0.506435	-0.272921	-0.368683	9.777271	0.020651	0.048629	-0.021450
+0.507457	-0.237010	-0.428534	9.750937	0.020384	0.047830	-0.021317
+0.508461	-0.260951	-0.363895	9.762907	0.021317	0.048496	-0.021850
+0.509463	-0.272921	-0.423746	9.789242	0.022516	0.048763	-0.021983
+0.510461	-0.263345	-0.438110	9.691086	0.023449	0.049429	-0.020784
+0.511455	-0.260951	-0.414169	9.758119	0.023449	0.048896	-0.019985
+0.512424	-0.268133	-0.423746	9.772483	0.022649	0.048629	-0.019718
+0.513389	-0.220252	-0.430928	9.786848	0.021450	0.049162	-0.020518
+0.514384	-0.258557	-0.435716	9.767695	0.021583	0.049162	-0.020917
+0.515385	-0.260951	-0.399805	9.779666	0.022516	0.049029	-0.021184
+0.516403	-0.246586	-0.409381	9.765301	0.021983	0.049962	-0.022383
+0.517427	-0.258557	-0.440504	9.784454	0.022383	0.049562	-0.021583
+0.518459	-0.311226	-0.428534	9.750937	0.023182	0.049429	-0.020251
+0.519460	-0.282497	-0.435716	9.707844	0.023182	0.048363	-0.020118
+0.520459	-0.239404	-0.397411	9.698268	0.023315	0.048896	-0.020917
+0.521463	-0.227434	-0.402199	9.710238	0.023715	0.049562	-0.021450
+0.522460	-0.225040	-0.380653	9.750937	0.023449	0.049162	-0.021184
+0.523462	-0.229828	-0.416563	9.760513	0.023182	0.049429	-0.020384
+0.524460	-0.237010	-0.409381	9.803606	0.024515	0.049828	-0.019452
+0.525461	-0.227434	-0.414169	9.729391	0.024914	0.049562	-0.019585
+0.526415	-0.265739	-0.438110	9.719814	0.024115	0.049029	-0.021717
+0.527433	-0.225040	-0.421352	9.806000	0.023848	0.049562	-0.020917
+0.528460	-0.239404	-0.402199	9.817970	0.023449	0.049695	-0.019851
+0.529458	-0.311226	-0.466838	9.810788	0.024381	0.049695	-0.019585
+0.530387	-0.292073	-0.430928	9.753331	0.024914	0.049296	-0.020518
+0.531384	-0.294467	-0.373471	9.782060	0.023715	0.049429	-0.020518
+0.532380	-0.246586	-0.457262	9.798818	0.023848	0.049695	-0.019452
+0.533363	-0.201100	-0.447686	9.736573	0.023449	0.049695	-0.020384
+0.534460	-0.258557	-0.478809	9.726997	0.023182	0.049296	-0.021450
+0.535461	-0.251375	-0.466838	9.669540	0.023182	0.048496	-0.020251
+0.536461	-0.229828	-0.428534	9.774877	0.023715	0.049162	-0.019452
+0.537476	-0.244192	-0.435716	9.789242	0.023848	0.049162	-0.018386
+0.538406	-0.244192	-0.447686	9.753331	0.022916	0.050628	-0.018786
+0.539457	-0.229828	-0.390229	9.679116	0.021717	0.050761	-0.020118
+0.540462	-0.292073	-0.450080	9.731785	0.021583	0.048629	-0.020384
+0.541463	-0.275315	-0.442898	9.789242	0.022916	0.047297	-0.020784
+0.542460	-0.277709	-0.423746	9.726997	0.023182	0.047697	-0.019718
+0.543460	-0.275315	-0.416563	9.707844	0.021850	0.047697	-0.020251
+0.544461	-0.270527	-0.406987	9.803606	0.020784	0.048763	-0.021184
+0.545424	-0.237010	-0.428534	9.806000	0.022250	0.048629	-0.020917
+0.546402	-0.263345	-0.402199	9.762907	0.022649	0.049296	-0.019052
+0.547385	-0.270527	-0.387835	9.777271	0.023315	0.050495	-0.018119
+0.548384	-0.210676	-0.447686	9.762907	0.022783	0.050495	-0.019185
+0.549386	-0.251375	-0.445292	9.777271	0.022383	0.048896	-0.019985
+0.550456	-0.251375	-0.416563	9.741361	0.022250	0.048763	-0.021850
+0.551460	-0.237010	-0.392623	9.731785	0.022116	0.049828	-0.021051
+0.552460	-0.222646	-0.375865	9.789242	0.022116	0.050761	-0.020118
+0.553463	-0.186735	-0.361500	9.774877	0.022649	0.049695	-0.018519
+0.554455	-0.179553	-0.354318	9.770089	0.022116	0.049296	-0.018652
+0.555462	-0.241798	-0.351924	9.710238	0.022116	0.049162	-0.020917
+0.556462	-0.244192	-0.416563	9.750937	0.022783	0.049296	-0.020251
+0.557462	-0.234616	-0.497961	9.726997	0.022783	0.049695	-0.020251
+0.558468	-0.263345	-0.459656	9.722208	0.023315	0.049429	-0.019851
+0.559418	-0.244192	-0.383047	9.772483	0.023182	0.049429	-0.020917
+0.560455	-0.292073	-0.418958	9.762907	0.022916	0.048629	-0.019985
+0.561418	-0.304043	-0.390229	9.741361	0.022783	0.047697	-0.019452
+0.562460	-0.258557	-0.426140	9.736573	0.022383	0.048230	-0.019185
+0.563396	-0.227434	-0.373471	9.801212	0.022916	0.049695	-0.020651
+0.564390	-0.248980	-0.368683	9.760513	0.023715	0.049162	-0.019585
+0.565380	-0.186735	-0.392623	9.710238	0.023449	0.048230	-0.018919
+0.566370	-0.203494	-0.399805	9.695874	0.021717	0.047164	-0.020118
+0.567361	-0.251375	-0.447686	9.750937	0.021850	0.048363	-0.019585
+0.568461	-0.260951	-0.445292	9.829940	0.022916	0.049828	-0.019185
+0.569463	-0.256163	-0.414169	9.839517	0.022649	0.048496	-0.019319
+0.570415	-0.234616	-0.383047	9.734179	0.022383	0.049162	-0.019319
+0.571438	-0.213070	-0.442898	9.784454	0.022783	0.048896	-0.018919
+0.572457	-0.260951	-0.442898	9.863457	0.023449	0.048629	-0.018386
+0.573461	-0.272921	-0.387835	9.736573	0.023982	0.049695	-0.020118
+0.574436	-0.229828	-0.354318	9.686298	0.024115	0.049562	-0.019585
+0.575396	-0.299255	-0.368683	9.753331	0.023715	0.049429	-0.018386
+0.576461	-0.270527	-0.402199	9.798818	0.023449	0.048763	-0.019052
+0.577417	-0.246586	-0.469232	9.810788	0.022649	0.049029	-0.019452
+0.578429	-0.229828	-0.438110	9.806000	0.021583	0.050495	-0.019985
+0.579361	-0.217858	-0.397411	9.786848	0.021717	0.050894	-0.019452
+0.580383	-0.229828	-0.318408	9.782060	0.023715	0.049429	-0.019052
+0.581385	-0.222646	-0.395017	9.810788	0.024381	0.048629	-0.019985
+0.582383	-0.246586	-0.426140	9.758119	0.024781	0.049429	-0.020651
+0.583385	-0.229828	-0.442898	9.691086	0.024381	0.050095	-0.018786
+0.584385	-0.239404	-0.411775	9.724603	0.024381	0.050095	-0.019052
+0.585385	-0.301649	-0.416563	9.750937	0.023315	0.049562	-0.018786
+0.586385	-0.282497	-0.440504	9.722208	0.022783	0.049562	-0.019585
+0.587385	-0.253769	-0.452474	9.803606	0.022783	0.049828	-0.019052
+0.588387	-0.248980	-0.481203	9.753331	0.023182	0.050628	-0.019985
+0.589362	-0.186735	-0.447686	9.698268	0.022783	0.051294	-0.020251
+0.590349	-0.265739	-0.411775	9.777271	0.022250	0.050228	-0.019718
+0.591462	-0.263345	-0.414169	9.734179	0.022383	0.049296	-0.019052
+0.592461	-0.227434	-0.438110	9.707844	0.021983	0.048230	-0.018119
+0.593458	-0.256163	-0.447686	9.741361	0.022783	0.049695	-0.018786
+0.594432	-0.225040	-0.471626	9.686298	0.022783	0.049828	-0.018519
+0.595456	-0.213070	-0.416563	9.770089	0.023449	0.049429	-0.018519
+0.596448	-0.205888	-0.339954	9.789242	0.023848	0.049029	-0.019585
+0.597388	-0.282497	-0.411775	9.755725	0.023715	0.049429	-0.021850
+0.598385	-0.287285	-0.435716	9.803606	0.024115	0.048896	-0.021184
+0.599384	-0.311226	-0.423746	9.765301	0.023049	0.049962	-0.021184
+0.600385	-0.292073	-0.445292	9.777271	0.021184	0.050228	-0.021850
+0.601408	-0.217858	-0.457262	9.784454	0.021450	0.050361	-0.021583
+0.602379	-0.177159	-0.402199	9.863457	0.022116	0.050495	-0.020917
+0.603408	-0.268133	-0.418958	9.796424	0.022516	0.050628	-0.020518
+0.604404	-0.248980	-0.411775	9.786848	0.022516	0.049695	-0.020118
+0.605407	-0.268133	-0.423746	9.865851	0.022783	0.050361	-0.020784
+0.606410	-0.241798	-0.418958	9.784454	0.022516	0.051427	-0.021317
+0.607455	-0.220252	-0.445292	9.753331	0.023182	0.050228	-0.021717
+0.608478	-0.263345	-0.395017	9.796424	0.022916	0.050095	-0.021051
+0.609502	-0.263345	-0.421352	9.777271	0.021983	0.049962	-0.020251
+0.610413	-0.244192	-0.421352	9.753331	0.021983	0.049695	-0.021317
+0.611434	-0.210676	-0.418958	9.849093	0.022649	0.050361	-0.022649
+0.612432	-0.189129	-0.402199	9.841911	0.023715	0.051028	-0.022383
+0.613394	-0.251375	-0.457262	9.703056	0.022916	0.051427	-0.021184
+0.614408	-0.232222	-0.466838	9.691086	0.022916	0.049162	-0.020784
+0.615407	-0.198706	-0.442898	9.729391	0.023182	0.048363	-0.021051
+0.616408	-0.263345	-0.409381	9.748543	0.023049	0.048763	-0.021983
+0.617370	-0.268133	-0.418958	9.794030	0.022649	0.050095	-0.022516
+0.618449	-0.282497	-0.454868	9.806000	0.022916	0.050228	-0.023315
+0.619392	-0.256163	-0.457262	9.758119	0.023715	0.050361	-0.021583
+0.620450	-0.270527	-0.435716	9.681510	0.023715	0.049162	-0.021450
+0.621452	-0.220252	-0.423746	9.762907	0.022516	0.049429	-0.020651
+0.622450	-0.220252	-0.387835	9.758119	0.022116	0.049562	-0.021051
+0.623447	-0.213070	-0.414169	9.657569	0.022916	0.049029	-0.020651
+0.624451	-0.189129	-0.442898	9.636023	0.022783	0.049029	-0.021317
+0.625452	-0.239404	-0.421352	9.671934	0.022250	0.050495	-0.021450
+0.626453	-0.265739	-0.368683	9.719814	0.022516	0.050095	-0.020118
+0.627393	-0.260951	-0.387835	9.782060	0.021317	0.048896	-0.021051
+0.628403	-0.251375	-0.411775	9.707844	0.022250	0.048363	-0.022516
+0.629443	-0.241798	-0.423746	9.772483	0.022516	0.050361	-0.022383
+0.630377	-0.251375	-0.445292	9.774877	0.023049	0.050495	-0.020384
+0.631372	-0.284891	-0.404593	9.832334	0.021583	0.050095	-0.019319
+0.632352	-0.217858	-0.409381	9.791636	0.022250	0.050495	-0.019718
+0.633453	-0.251375	-0.450080	9.729391	0.021317	0.050761	-0.019585
+0.634451	-0.272921	-0.497961	9.700662	0.022383	0.049162	-0.020118
+0.635411	-0.222646	-0.490779	9.746149	0.022383	0.048763	-0.019985
+0.636409	-0.232222	-0.428534	9.691086	0.021317	0.049429	-0.020917
+0.637453	-0.251375	-0.442898	9.705450	0.019851	0.048763	-0.022116
+0.638388	-0.220252	-0.430928	9.798818	0.020384	0.049962	-0.021450
+0.639422	-0.167583	-0.371077	9.777271	0.020384	0.050228	-0.021184
+0.640448	-0.253769	-0.375865	9.748543	0.021317	0.050228	-0.021184
+0.641454	-0.282497	-0.452474	9.794030	0.020251	0.049962	-0.021184
+0.642451	-0.275315	-0.442898	9.789242	0.020118	0.048496	-0.021583
+0.643452	-0.215464	-0.490779	9.837123	0.020384	0.049695	-0.020784
+0.644452	-0.256163	-0.466838	9.892186	0.020917	0.050761	-0.019851
+0.645435	-0.306437	-0.418958	9.760513	0.021184	0.050894	-0.020917
+0.646376	-0.294467	-0.433322	9.741361	0.020651	0.049429	-0.021850
+0.647364	-0.251375	-0.380653	9.755725	0.020118	0.048096	-0.020118
+0.648369	-0.248980	-0.430928	9.806000	0.019851	0.048363	-0.021184
+0.649408	-0.172371	-0.428534	9.736573	0.018919	0.048496	-0.021983
+0.650394	-0.217858	-0.390229	9.808394	0.019185	0.049429	-0.020384
+0.651389	-0.189129	-0.442898	9.813182	0.019851	0.049296	-0.020784
+0.652448	-0.234616	-0.474021	9.777271	0.020251	0.049429	-0.021450
+0.653405	-0.213070	-0.375865	9.741361	0.019985	0.050628	-0.023049
+0.654399	-0.222646	-0.387835	9.770089	0.019452	0.051560	-0.024381
+0.655401	-0.244192	-0.390229	9.803606	0.018386	0.050628	-0.023582
+0.656403	-0.210676	-0.380653	9.731785	0.017720	0.048496	-0.020118
+0.657453	-0.203494	-0.409381	9.813182	0.018253	0.048896	-0.018786
+0.658455	-0.244192	-0.435716	9.822758	0.018119	0.050095	-0.021717
+0.659413	-0.246586	-0.481203	9.712632	0.018119	0.049562	-0.023182
+0.660350	-0.229828	-0.409381	9.676722	0.018786	0.049828	-0.021583
+0.661356	-0.237010	-0.395017	9.729391	0.018119	0.049828	-0.020651
+0.662419	-0.256163	-0.351924	9.669540	0.016787	0.050495	-0.020384
+0.663391	-0.232222	-0.344742	9.755725	0.017187	0.050361	-0.021583
+0.664374	-0.215464	-0.383047	9.717420	0.017853	0.050361	-0.021317
+0.665409	-0.215464	-0.426140	9.650387	0.019052	0.049828	-0.021983
+0.666407	-0.208282	-0.430928	9.827546	0.019052	0.049828	-0.022916
+0.667425	-0.227434	-0.418958	9.870639	0.019052	0.050228	-0.022383
+0.668489	-0.217858	-0.416563	9.777271	0.019585	0.050095	-0.022649
+0.669482	-0.272921	-0.406987	9.789242	0.019718	0.050095	-0.022116
+0.670487	-0.225040	-0.385441	9.703056	0.018652	0.049962	-0.020917
+0.671488	-0.215464	-0.380653	9.712632	0.019452	0.049296	-0.021317
+0.672456	-0.203494	-0.404593	9.791636	0.019319	0.048496	-0.021983
+0.673481	-0.251375	-0.397411	9.784454	0.019585	0.048363	-0.023315
+0.674487	-0.260951	-0.380653	9.829940	0.020518	0.050495	-0.023449
+0.675489	-0.248980	-0.363895	9.782060	0.021184	0.050228	-0.021983
+0.676490	-0.280103	-0.402199	9.726997	0.021184	0.049162	-0.020651
+0.677423	-0.289679	-0.459656	9.707844	0.019985	0.049029	-0.019851
+0.678489	-0.229828	-0.411775	9.748543	0.019718	0.049296	-0.021184
+0.679411	-0.220252	-0.426140	9.748543	0.019052	0.050628	-0.022649
+0.680410	-0.256163	-0.414169	9.738967	0.021317	0.050228	-0.023049
+0.681408	-0.263345	-0.433322	9.753331	0.021450	0.049296	-0.021317
+0.682406	-0.263345	-0.409381	9.710238	0.020251	0.050228	-0.021051
+0.683407	-0.272921	-0.387835	9.770089	0.020518	0.049962	-0.022383
+0.684406	-0.304043	-0.404593	9.746149	0.019585	0.049828	-0.020917
+0.685486	-0.270527	-0.435716	9.772483	0.019718	0.049962	-0.019718
+0.686490	-0.241798	-0.421352	9.808394	0.020251	0.049828	-0.020251
+0.687489	-0.215464	-0.402199	9.801212	0.021317	0.048896	-0.020784
+0.688490	-0.270527	-0.404593	9.810788	0.021583	0.048496	-0.020917
+0.689490	-0.320802	-0.378259	9.813182	0.022116	0.047830	-0.021184
+0.690489	-0.263345	-0.430928	9.782060	0.020784	0.047564	-0.019585
+0.691488	-0.239404	-0.426140	9.774877	0.020251	0.048496	-0.019319
+0.692452	-0.248980	-0.404593	9.691086	0.021184	0.049429	-0.020251
+0.693449	-0.251375	-0.457262	9.750937	0.021983	0.049296	-0.020118
+0.694489	-0.217858	-0.411775	9.777271	0.021583	0.049562	-0.020784
+0.695488	-0.186735	-0.402199	9.688692	0.021717	0.050495	-0.021184
+0.696426	-0.205888	-0.397411	9.839517	0.021184	0.051427	-0.022116
+0.697411	-0.234616	-0.368683	9.789242	0.021450	0.049695	-0.021184
+0.698406	-0.284891	-0.404593	9.762907	0.022916	0.048230	-0.020384
+0.699407	-0.301649	-0.361500	9.789242	0.023049	0.049962	-0.019452
+0.700406	-0.268133	-0.418958	9.729391	0.023182	0.048763	-0.018519
+0.701360	-0.225040	-0.459656	9.806000	0.022516	0.048896	-0.020251
+0.702404	-0.198706	-0.438110	9.820364	0.022116	0.049695	-0.020384
+0.703405	-0.210676	-0.447686	9.770089	0.022649	0.048896	-0.020518
+0.704396	-0.241798	-0.390229	9.820364	0.023582	0.049562	-0.021317
+0.705404	-0.198706	-0.423746	9.798818	0.023582	0.049695	-0.021184
+0.706401	-0.256163	-0.454868	9.743755	0.023315	0.048763	-0.020518
+0.707450	-0.256163	-0.404593	9.777271	0.023982	0.048763	-0.020518
+0.708451	-0.213070	-0.411775	9.758119	0.023449	0.048629	-0.021983
+0.709449	-0.210676	-0.435716	9.772483	0.023582	0.047430	-0.021717
+0.710450	-0.177159	-0.399805	9.786848	0.023848	0.049029	-0.019851
+0.711451	-0.225040	-0.402199	9.791636	0.024115	0.048496	-0.018519
+0.712436	-0.244192	-0.442898	9.741361	0.024115	0.049429	-0.019185
+0.713410	-0.272921	-0.454868	9.851487	0.025314	0.050894	-0.020651
+0.714407	-0.239404	-0.418958	9.806000	0.024648	0.049962	-0.021850
+0.715407	-0.246586	-0.409381	9.738967	0.024781	0.049429	-0.019851
+0.716402	-0.268133	-0.375865	9.772483	0.024381	0.048896	-0.019452
+0.717403	-0.272921	-0.356712	9.822758	0.023315	0.049296	-0.020384
+0.718424	-0.210676	-0.392623	9.777271	0.022649	0.050361	-0.021051
+0.719426	-0.213070	-0.423746	9.784454	0.024115	0.049962	-0.021450
+0.720426	-0.282497	-0.395017	9.777271	0.024515	0.050761	-0.021317
+0.721489	-0.282497	-0.366289	9.726997	0.024781	0.049162	-0.022383
+0.722487	-0.275315	-0.373471	9.734179	0.024648	0.048496	-0.022116
+0.723489	-0.301649	-0.383047	9.808394	0.023582	0.049429	-0.022250
+0.724441	-0.225040	-0.397411	9.808394	0.023315	0.051028	-0.022383
+0.725457	-0.284891	-0.459656	9.726997	0.023182	0.050628	-0.023049
+0.726494	-0.241798	-0.505143	9.734179	0.022916	0.050628	-0.022916
+0.727420	-0.244192	-0.452474	9.765301	0.024248	0.050228	-0.022250
+0.728486	-0.246586	-0.454868	9.705450	0.024914	0.049695	-0.021983
+0.729488	-0.258557	-0.438110	9.765301	0.024381	0.049828	-0.021583
+0.730422	-0.275315	-0.469232	9.815576	0.023582	0.050628	-0.021317
+0.731406	-0.258557	-0.445292	9.801212	0.023182	0.051560	-0.020518
+0.732407	-0.251375	-0.387835	9.777271	0.024515	0.051028	-0.020917
+0.733401	-0.244192	-0.452474	9.703056	0.024381	0.050761	-0.022516
+0.734405	-0.201100	-0.452474	9.681510	0.022516	0.050894	-0.023049
+0.735423	-0.172371	-0.395017	9.760513	0.021983	0.050361	-0.023182
+0.736428	-0.203494	-0.418958	9.760513	0.021717	0.049562	-0.023582
+0.737435	-0.263345	-0.411775	9.712632	0.022516	0.049162	-0.022516
+0.738487	-0.287285	-0.433322	9.770089	0.021983	0.049562	-0.020651
+0.739489	-0.284891	-0.433322	9.827546	0.021450	0.050894	-0.020518
+0.740486	-0.196312	-0.406987	9.829940	0.021850	0.051694	-0.020917
+0.741488	-0.215464	-0.414169	9.712632	0.022783	0.051960	-0.022250
+0.742487	-0.208282	-0.452474	9.743755	0.022649	0.050894	-0.021317
+0.743488	-0.217858	-0.435716	9.750937	0.022649	0.049962	-0.022783
+0.744459	-0.234616	-0.402199	9.825152	0.021583	0.051161	-0.022916
+0.745442	-0.184341	-0.371077	9.779666	0.020784	0.050761	-0.022116
+0.746415	-0.275315	-0.416563	9.767695	0.021850	0.052093	-0.023049
+0.747406	-0.306437	-0.466838	9.808394	0.022783	0.051960	-0.022916
+0.748407	-0.246586	-0.426140	9.777271	0.021983	0.050761	-0.023449
+0.749407	-0.205888	-0.418958	9.789242	0.021983	0.050495	-0.023982
+0.750407	-0.229828	-0.390229	9.849093	0.020118	0.050628	-0.023582
+0.751403	-0.258557	-0.426140	9.796424	0.019851	0.050894	-0.022916
+0.752488	-0.220252	-0.416563	9.750937	0.020384	0.050628	-0.022116
+0.753514	-0.246586	-0.406987	9.671934	0.020784	0.050495	-0.022516
+0.754511	-0.217858	-0.383047	9.772483	0.021583	0.050361	-0.023848
+0.755455	-0.265739	-0.395017	9.746149	0.021583	0.050228	-0.023582
+0.756507	-0.256163	-0.435716	9.767695	0.021450	0.050361	-0.021317
+0.757514	-0.246586	-0.423746	9.750937	0.020251	0.050495	-0.022783
+0.758510	-0.246586	-0.409381	9.717420	0.019851	0.050495	-0.025980
+0.759511	-0.220252	-0.409381	9.710238	0.019319	0.051694	-0.023449
+0.760512	-0.220252	-0.373471	9.784454	0.019319	0.051960	-0.021983
+0.761448	-0.280103	-0.387835	9.786848	0.019185	0.051694	-0.021983
+0.762427	-0.256163	-0.409381	9.849093	0.018919	0.049962	-0.021450
+0.763426	-0.227434	-0.435716	9.717420	0.018386	0.048496	-0.021717
+0.764421	-0.258557	-0.414169	9.712632	0.017986	0.050894	-0.022916
+0.765420	-0.313620	-0.428534	9.803606	0.019185	0.051694	-0.023449
+0.766437	-0.280103	-0.409381	9.760513	0.020118	0.049562	-0.023049
+0.767436	-0.237010	-0.385441	9.758119	0.021051	0.050095	-0.022250
+0.768418	-0.237010	-0.385441	9.758119	0.020917	0.052093	-0.023449
+0.769417	-0.241798	-0.474021	9.817970	0.021317	0.053959	-0.024115
+0.770414	-0.229828	-0.490779	9.851487	0.021317	0.050495	-0.023582
+0.771420	-0.215464	-0.378259	9.806000	0.020651	0.048629	-0.023315
+0.772441	-0.189129	-0.373471	9.810788	0.019985	0.051028	-0.022783
+0.773444	-0.217858	-0.395017	9.736573	0.020651	0.051694	-0.023315
+0.774443	-0.213070	-0.428534	9.779666	0.021983	0.049828	-0.023315
+0.775449	-0.229828	-0.440504	9.813182	0.021583	0.050628	-0.023715
+0.776446	-0.260951	-0.442898	9.817970	0.021450	0.052093	-0.023049
+0.777493	-0.215464	-0.450080	9.772483	0.020651	0.052626	-0.023049
+0.778442	-0.198706	-0.421352	9.875427	0.020118	0.052626	-0.021983
+0.779447	-0.189129	-0.445292	9.794030	0.020384	0.051028	-0.021317
+0.780432	-0.253769	-0.464444	9.662357	0.019585	0.050361	-0.021583
+0.781400	-0.241798	-0.452474	9.707844	0.019585	0.052360	-0.023182
+0.782401	-0.260951	-0.457262	9.815576	0.019319	0.052227	-0.022250
+0.783400	-0.277709	-0.469232	9.753331	0.019185	0.050228	-0.020518
+0.784395	-0.265739	-0.409381	9.753331	0.019718	0.050761	-0.020917
+0.785404	-0.234616	-0.387835	9.729391	0.019718	0.048230	-0.021317
+0.786404	-0.246586	-0.421352	9.734179	0.020518	0.047430	-0.022916
+0.787403	-0.263345	-0.418958	9.707844	0.020651	0.049296	-0.023315
+0.788395	-0.232222	-0.450080	9.774877	0.021184	0.050361	-0.022116
+0.789406	-0.225040	-0.390229	9.772483	0.020384	0.050361	-0.022916
+0.790400	-0.239404	-0.390229	9.767695	0.019851	0.049828	-0.023049
+0.791403	-0.205888	-0.354318	9.746149	0.019452	0.048096	-0.023315
+0.792401	-0.256163	-0.387835	9.782060	0.020384	0.048096	-0.021317
+0.793404	-0.239404	-0.399805	9.827546	0.019718	0.048896	-0.021583
+0.794401	-0.272921	-0.395017	9.743755	0.020251	0.049562	-0.021717
+0.795401	-0.239404	-0.380653	9.738967	0.020917	0.050228	-0.020251
+0.796417	-0.287285	-0.459656	9.782060	0.020118	0.049828	-0.021051
+0.797433	-0.246586	-0.507537	9.820364	0.019319	0.048896	-0.021717
+0.798436	-0.294467	-0.469232	9.736573	0.020384	0.049562	-0.023182
+0.799438	-0.268133	-0.459656	9.712632	0.021051	0.050228	-0.023582
+0.800429	-0.301649	-0.416563	9.691086	0.020384	0.051294	-0.022516
+0.801438	-0.282497	-0.375865	9.774877	0.019851	0.050361	-0.021717
+0.802437	-0.234616	-0.349530	9.827546	0.020384	0.050228	-0.021583
+0.803423	-0.318408	-0.452474	9.806000	0.020384	0.049695	-0.022383
+0.804419	-0.260951	-0.421352	9.849093	0.019718	0.049695	-0.022116
+0.805425	-0.215464	-0.430928	9.827546	0.019985	0.049695	-0.023315
+0.806445	-0.205888	-0.397411	9.729391	0.020118	0.049562	-0.023715
+0.807443	-0.234616	-0.404593	9.796424	0.020118	0.049429	-0.020917
+0.808443	-0.258557	-0.445292	9.841911	0.019185	0.048896	-0.019319
+0.809438	-0.225040	-0.399805	9.784454	0.018919	0.049695	-0.020518
+0.810449	-0.294467	-0.438110	9.755725	0.019452	0.050894	-0.023049
+0.811444	-0.277709	-0.430928	9.762907	0.020384	0.050628	-0.024914
+0.812520	-0.268133	-0.414169	9.688692	0.020384	0.049162	-0.025047
+0.813428	-0.313620	-0.462050	9.683904	0.021317	0.049695	-0.021983
+0.814419	-0.244192	-0.414169	9.755725	0.022516	0.050361	-0.019985
+0.815418	-0.299255	-0.423746	9.782060	0.021317	0.050095	-0.019585
+0.816418	-0.318408	-0.442898	9.827546	0.021450	0.050095	-0.019718
+0.817414	-0.306437	-0.430928	9.851487	0.023049	0.050894	-0.019319
+0.818414	-0.253769	-0.488385	9.875427	0.023315	0.050761	-0.019985
+0.819418	-0.177159	-0.411775	9.798818	0.021583	0.049562	-0.020651
+0.820507	-0.239404	-0.395017	9.729391	0.020251	0.048363	-0.020651
+0.821444	-0.270527	-0.392623	9.750937	0.020518	0.048496	-0.020384
+0.822442	-0.241798	-0.435716	9.760513	0.020384	0.049162	-0.021717
+0.823498	-0.222646	-0.459656	9.722208	0.020384	0.049562	-0.020917
+0.824442	-0.260951	-0.442898	9.772483	0.020518	0.049562	-0.019452
+0.825502	-0.237010	-0.421352	9.810788	0.021184	0.051028	-0.019319
+0.826502	-0.213070	-0.404593	9.789242	0.022116	0.051827	-0.019718
+0.827448	-0.201100	-0.440504	9.839517	0.024248	0.049429	-0.021717
+0.828421	-0.275315	-0.416563	9.796424	0.024648	0.048496	-0.022649
+0.829398	-0.260951	-0.471626	9.755725	0.025047	0.049429	-0.021450
+0.830382	-0.191523	-0.445292	9.796424	0.025447	0.049429	-0.022916
+0.831398	-0.251375	-0.354318	9.741361	0.023182	0.049962	-0.021317
+0.832398	-0.263345	-0.354318	9.691086	0.021450	0.049562	-0.020518
+0.833371	-0.260951	-0.406987	9.755725	0.022250	0.049429	-0.019851
+0.834372	-0.220252	-0.411775	9.750937	0.023049	0.048896	-0.019985
+0.835371	-0.208282	-0.395017	9.724603	0.022649	0.047564	-0.020518
+0.836372	-0.203494	-0.368683	9.676722	0.022383	0.048096	-0.021850
+0.837372	-0.294467	-0.390229	9.750937	0.023182	0.049029	-0.020917
+0.838372	-0.272921	-0.409381	9.794030	0.022916	0.049562	-0.020518
+0.839371	-0.256163	-0.416563	9.815576	0.023049	0.048896	-0.022516
+0.840372	-0.246586	-0.397411	9.825152	0.023182	0.048629	-0.019985
+0.841372	-0.280103	-0.392623	9.837123	0.021450	0.047963	-0.017587
+0.842372	-0.320802	-0.392623	9.743755	0.021450	0.049029	-0.019585
+0.843372	-0.323196	-0.380653	9.695874	0.021583	0.049296	-0.019718
+0.844372	-0.248980	-0.409381	9.820364	0.022916	0.048496	-0.019851
+0.845372	-0.225040	-0.438110	9.779666	0.023848	0.048230	-0.021583
+0.846372	-0.251375	-0.423746	9.760513	0.024248	0.048763	-0.022649
+0.847372	-0.258557	-0.423746	9.765301	0.024781	0.049828	-0.020784
+0.848390	-0.239404	-0.409381	9.782060	0.023982	0.049296	-0.019985
+0.849372	-0.232222	-0.383047	9.839517	0.024515	0.049162	-0.020118
+0.850372	-0.191523	-0.383047	9.813182	0.024381	0.049695	-0.019851
+0.851371	-0.217858	-0.435716	9.722208	0.024781	0.051294	-0.020917
+0.852372	-0.277709	-0.452474	9.705450	0.024781	0.050628	-0.022116
+0.853373	-0.265739	-0.476415	9.796424	0.024515	0.049828	-0.021184
+0.854372	-0.246586	-0.485991	9.829940	0.024115	0.050228	-0.019585
+0.855372	-0.294467	-0.483597	9.808394	0.022516	0.049429	-0.019452
+0.856372	-0.284891	-0.450080	9.825152	0.021450	0.049695	-0.022116
+0.857371	-0.260951	-0.404593	9.786848	0.022383	0.049429	-0.022516
+0.858372	-0.270527	-0.416563	9.741361	0.023182	0.048629	-0.023449
+0.859372	-0.227434	-0.481203	9.698268	0.023049	0.047430	-0.021983
+0.860373	-0.229828	-0.478809	9.715026	0.022516	0.047697	-0.021450
+0.861373	-0.244192	-0.426140	9.762907	0.023182	0.049828	-0.020251
+0.862389	-0.205888	-0.411775	9.741361	0.022916	0.050361	-0.019718
+0.863368	-0.256163	-0.466838	9.777271	0.023982	0.050228	-0.019985
+0.864355	-0.284891	-0.457262	9.741361	0.024115	0.049828	-0.019851
+0.865353	-0.287285	-0.430928	9.820364	0.023982	0.051028	-0.020118
+0.866367	-0.205888	-0.433322	9.789242	0.023315	0.051294	-0.021717
+0.867362	-0.251375	-0.440504	9.712632	0.022649	0.051560	-0.020651
+0.868371	-0.268133	-0.402199	9.726997	0.022250	0.050228	-0.018652
+0.869372	-0.299255	-0.426140	9.832334	0.021983	0.047830	-0.020384
+0.870373	-0.222646	-0.416563	9.719814	0.022783	0.047297	-0.022116
+0.871372	-0.189129	-0.469232	9.741361	0.023049	0.049962	-0.021983
+0.872372	-0.213070	-0.433322	9.729391	0.021583	0.050628	-0.022116
+0.873372	-0.227434	-0.354318	9.755725	0.021051	0.049962	-0.022383
+0.874366	-0.196312	-0.416563	9.762907	0.019985	0.049162	-0.021317
+0.875372	-0.258557	-0.442898	9.796424	0.021317	0.048096	-0.022116
+0.876376	-0.258557	-0.416563	9.801212	0.022916	0.049162	-0.021850
+0.877372	-0.251375	-0.452474	9.695874	0.021051	0.050894	-0.020384
+0.878373	-0.263345	-0.454868	9.765301	0.019452	0.050628	-0.021051
+0.879372	-0.265739	-0.416563	9.755725	0.020518	0.048496	-0.021850
+0.880371	-0.244192	-0.438110	9.762907	0.021983	0.048496	-0.022916
+0.881372	-0.241798	-0.435716	9.789242	0.021717	0.048763	-0.021450
+0.882372	-0.222646	-0.404593	9.767695	0.021583	0.048896	-0.021850
+0.883372	-0.272921	-0.445292	9.755725	0.020784	0.050228	-0.020251
+0.884371	-0.241798	-0.442898	9.777271	0.020651	0.049962	-0.020917
+0.885372	-0.217858	-0.411775	9.794030	0.020384	0.048896	-0.021983
+0.886372	-0.172371	-0.375865	9.832334	0.021850	0.048896	-0.022383
+0.887372	-0.232222	-0.397411	9.782060	0.021184	0.049429	-0.022250
+0.888372	-0.201100	-0.426140	9.853881	0.020251	0.050761	-0.021184
+0.889371	-0.251375	-0.464444	9.829940	0.020917	0.050095	-0.020251
+0.890372	-0.237010	-0.469232	9.822758	0.021051	0.049962	-0.019985
+0.891384	-0.258557	-0.416563	9.801212	0.020784	0.050761	-0.021450
+0.892374	-0.258557	-0.445292	9.827546	0.021983	0.050894	-0.022383
+0.893372	-0.227434	-0.447686	9.750937	0.021850	0.048629	-0.023449
+0.894386	-0.289679	-0.404593	9.772483	0.022916	0.047430	-0.022116
+0.895401	-0.239404	-0.423746	9.817970	0.022516	0.048629	-0.020784
+0.896373	-0.215464	-0.404593	9.750937	0.022783	0.050095	-0.021983
+0.897374	-0.229828	-0.385441	9.770089	0.021983	0.049162	-0.023449
+0.898387	-0.237010	-0.414169	9.722208	0.021184	0.049562	-0.022783
+0.899370	-0.234616	-0.493173	9.726997	0.020917	0.050361	-0.021450
+0.900397	-0.210676	-0.445292	9.798818	0.022516	0.048763	-0.019585
+0.901404	-0.256163	-0.438110	9.743755	0.022116	0.048096	-0.019585
+0.902399	-0.205888	-0.387835	9.734179	0.021983	0.047430	-0.019718
+0.903399	-0.237010	-0.418958	9.729391	0.021983	0.047830	-0.021184
+0.904387	-0.301649	-0.392623	9.777271	0.021850	0.049162	-0.022516
+0.905396	-0.256163	-0.397411	9.770089	0.022383	0.049029	-0.020384
+0.906402	-0.213070	-0.418958	9.753331	0.021850	0.049162	-0.019718
+0.907401	-0.248980	-0.447686	9.710238	0.021317	0.049296	-0.021184
+0.908401	-0.253769	-0.466838	9.774877	0.021317	0.050361	-0.020651
+0.909404	-0.237010	-0.438110	9.837123	0.021317	0.050095	-0.020518
+0.910400	-0.296861	-0.402199	9.817970	0.021317	0.049296	-0.020518
+0.911401	-0.284891	-0.373471	9.770089	0.020784	0.048363	-0.020118
+0.912371	-0.246586	-0.392623	9.798818	0.021850	0.049562	-0.021051
+0.913418	-0.260951	-0.423746	9.808394	0.021184	0.050228	-0.019985
+0.914418	-0.237010	-0.438110	9.822758	0.021051	0.049162	-0.019319
+0.915418	-0.220252	-0.450080	9.827546	0.021450	0.048629	-0.021317
+0.916408	-0.203494	-0.428534	9.844305	0.021717	0.049962	-0.021717
+0.917451	-0.220252	-0.414169	9.841911	0.023582	0.050628	-0.021184
+0.918449	-0.225040	-0.409381	9.834729	0.024515	0.050495	-0.020251
+0.919451	-0.225040	-0.435716	9.794030	0.023715	0.049562	-0.022116
+0.920452	-0.217858	-0.442898	9.829940	0.022516	0.048629	-0.022649
+0.921450	-0.256163	-0.450080	9.832334	0.022649	0.047830	-0.022250
+0.922451	-0.311226	-0.368683	9.815576	0.022516	0.049296	-0.020384
+0.923451	-0.258557	-0.426140	9.837123	0.022516	0.049828	-0.021317
+0.924451	-0.237010	-0.435716	9.889792	0.023049	0.048629	-0.021583
+0.925435	-0.227434	-0.383047	9.839517	0.023449	0.048496	-0.020784
+0.926463	-0.239404	-0.440504	9.779666	0.024381	0.048896	-0.020917
+0.927451	-0.246586	-0.481203	9.849093	0.023982	0.049562	-0.021051
+0.928379	-0.253769	-0.485991	9.741361	0.023315	0.049695	-0.021184
+0.929452	-0.196312	-0.416563	9.806000	0.024248	0.049962	-0.019851
+0.930378	-0.203494	-0.366289	9.791636	0.025580	0.049029	-0.020251
+0.931364	-0.237010	-0.421352	9.767695	0.024648	0.048896	-0.021317
+0.932385	-0.246586	-0.375865	9.750937	0.022916	0.050095	-0.019851
+0.933450	-0.222646	-0.404593	9.765301	0.022516	0.050894	-0.021184
+0.934446	-0.229828	-0.397411	9.681510	0.023315	0.049962	-0.020651
+0.935437	-0.217858	-0.464444	9.652781	0.023715	0.050361	-0.021184
+0.936423	-0.201100	-0.471626	9.734179	0.022516	0.050095	-0.022649
+0.937457	-0.246586	-0.426140	9.741361	0.020917	0.051161	-0.021317
+0.938447	-0.201100	-0.423746	9.758119	0.019985	0.050228	-0.020651
+0.939411	-0.186735	-0.371077	9.844305	0.021317	0.049695	-0.020917
+0.940450	-0.229828	-0.418958	9.782060	0.021317	0.050495	-0.020917
+0.941451	-0.256163	-0.418958	9.755725	0.021184	0.048496	-0.021583
+0.942449	-0.256163	-0.447686	9.794030	0.021317	0.047963	-0.022516
+0.943447	-0.263345	-0.428534	9.801212	0.020917	0.048629	-0.022116
+0.944449	-0.232222	-0.426140	9.784454	0.020651	0.050228	-0.021983
+0.945408	-0.253769	-0.390229	9.758119	0.021450	0.049962	-0.021051
+0.946379	-0.277709	-0.366289	9.774877	0.021051	0.049962	-0.021717
+0.947370	-0.277709	-0.433322	9.724603	0.020784	0.050361	-0.020917
+0.948355	-0.301649	-0.488385	9.700662	0.021850	0.049962	-0.020118
+0.949467	-0.284891	-0.495567	9.808394	0.021983	0.050228	-0.020518
+0.950399	-0.246586	-0.409381	9.889792	0.021717	0.049162	-0.020917
+0.951446	-0.227434	-0.373471	9.801212	0.022383	0.049562	-0.021184
+0.952451	-0.232222	-0.416563	9.664751	0.022516	0.050228	-0.020384
+0.953451	-0.229828	-0.402199	9.691086	0.022783	0.050228	-0.019052
+0.954451	-0.253769	-0.366289	9.820364	0.022116	0.050228	-0.019718
+0.955451	-0.217858	-0.399805	9.794030	0.021717	0.049962	-0.022116
+0.956446	-0.251375	-0.440504	9.837123	0.022116	0.049962	-0.023182
+0.957465	-0.239404	-0.404593	9.810788	0.023715	0.050095	-0.021850
+0.958433	-0.222646	-0.406987	9.772483	0.023715	0.049562	-0.020118
+0.959459	-0.225040	-0.440504	9.887397	0.023582	0.048896	-0.020518
+0.960450	-0.229828	-0.397411	9.782060	0.023049	0.050361	-0.023449
+0.961432	-0.184341	-0.430928	9.738967	0.022916	0.050628	-0.022783
+0.962405	-0.193917	-0.411775	9.729391	0.025580	0.049828	-0.023049
+0.963373	-0.260951	-0.414169	9.784454	0.026113	0.050628	-0.021450
+0.964372	-0.220252	-0.359106	9.798818	0.025847	0.050361	-0.021850
+0.965383	-0.198706	-0.387835	9.815576	0.024381	0.049695	-0.022116
+0.966451	-0.229828	-0.452474	9.772483	0.025447	0.050628	-0.020384
+0.967453	-0.248980	-0.423746	9.691086	0.026646	0.050361	-0.020518
+0.968449	-0.272921	-0.438110	9.731785	0.026113	0.049828	-0.021317
+0.969439	-0.222646	-0.497961	9.806000	0.025847	0.050628	-0.021983
+0.970451	-0.169977	-0.469232	9.794030	0.026380	0.050628	-0.021983
+0.971449	-0.237010	-0.414169	9.760513	0.025580	0.051028	-0.023182
+0.972451	-0.256163	-0.404593	9.772483	0.024515	0.051427	-0.021850
+0.973446	-0.198706	-0.435716	9.827546	0.026247	0.050761	-0.021184
+0.974449	-0.256163	-0.375865	9.782060	0.027046	0.048496	-0.021450
+0.975451	-0.316014	-0.409381	9.808394	0.027446	0.048763	-0.020917
+0.976451	-0.277709	-0.402199	9.738967	0.026113	0.051427	-0.020518
+0.977449	-0.251375	-0.466838	9.808394	0.026247	0.051827	-0.021850
+0.978399	-0.284891	-0.402199	9.779666	0.027179	0.050361	-0.022649
+0.979374	-0.239404	-0.418958	9.798818	0.027845	0.049828	-0.022783
+0.980373	-0.225040	-0.406987	9.738967	0.028112	0.049828	-0.020651
+0.981371	-0.244192	-0.397411	9.741361	0.027179	0.050228	-0.019851
+0.982371	-0.301649	-0.380653	9.710238	0.025980	0.050095	-0.021184
+0.983395	-0.232222	-0.399805	9.722208	0.026380	0.049828	-0.022916
+0.984394	-0.258557	-0.416563	9.741361	0.027179	0.050228	-0.022250
+0.985399	-0.275315	-0.466838	9.669540	0.026779	0.050761	-0.020518
+0.986399	-0.270527	-0.416563	9.712632	0.027179	0.050228	-0.019185
+0.987399	-0.251375	-0.411775	9.758119	0.026646	0.049562	-0.018652
+0.988399	-0.275315	-0.452474	9.815576	0.027312	0.049695	-0.022516
+0.989398	-0.232222	-0.428534	9.743755	0.027446	0.050628	-0.020917
+0.990369	-0.253769	-0.414169	9.750937	0.027579	0.050361	-0.019985
+0.991373	-0.292073	-0.457262	9.750937	0.028378	0.049828	-0.019851
+0.992373	-0.246586	-0.469232	9.748543	0.028778	0.049296	-0.021583
+0.993398	-0.301649	-0.430928	9.813182	0.028511	0.049562	-0.021583
+0.994398	-0.268133	-0.366289	9.794030	0.028645	0.048363	-0.019718
+0.995399	-0.251375	-0.359106	9.750937	0.029711	0.047963	-0.019319
+0.996373	-0.227434	-0.445292	9.738967	0.029178	0.049695	-0.020917
+0.997374	-0.234616	-0.402199	9.791636	0.029311	0.050761	-0.021184
+0.998371	-0.268133	-0.454868	9.786848	0.029444	0.049695	-0.021717
+0.999374	-0.268133	-0.387835	9.789242	0.030110	0.049429	-0.019851
+1.000373	-0.258557	-0.366289	9.746149	0.029977	0.048763	-0.019718
+1.001373	-0.229828	-0.395017	9.832334	0.029577	0.049296	-0.021184
+1.002373	-0.258557	-0.428534	9.803606	0.030510	0.050095	-0.021983
+1.003373	-0.265739	-0.445292	9.791636	0.030510	0.051294	-0.020384
+1.004373	-0.191523	-0.371077	9.889792	0.031309	0.051028	-0.017320
+1.005374	-0.244192	-0.433322	9.762907	0.030510	0.050628	-0.017054
+1.006374	-0.275315	-0.411775	9.734179	0.030243	0.049695	-0.021583
+1.007369	-0.244192	-0.361500	9.738967	0.029444	0.050628	-0.021450
+1.008373	-0.196312	-0.387835	9.801212	0.029844	0.050361	-0.019718
+1.009374	-0.203494	-0.368683	9.741361	0.029977	0.049429	-0.020384
+1.010374	-0.205888	-0.414169	9.844305	0.030243	0.050628	-0.020651
+1.011370	-0.232222	-0.406987	9.817970	0.029444	0.049962	-0.020251
+1.012369	-0.237010	-0.406987	9.746149	0.030110	0.049695	-0.020651
+1.013374	-0.251375	-0.383047	9.794030	0.029444	0.049029	-0.020251
+1.014373	-0.277709	-0.354318	9.738967	0.029577	0.047430	-0.020384
+1.015372	-0.239404	-0.406987	9.734179	0.030243	0.047830	-0.019319
+1.016369	-0.227434	-0.438110	9.758119	0.030243	0.049695	-0.019452
+1.017375	-0.225040	-0.430928	9.743755	0.029044	0.050361	-0.019452
+1.018373	-0.234616	-0.430928	9.767695	0.028645	0.050095	-0.019185
+1.019373	-0.225040	-0.402199	9.798818	0.028911	0.050628	-0.020384
+1.020369	-0.237010	-0.368683	9.806000	0.030910	0.049562	-0.019452
+1.021373	-0.316014	-0.462050	9.813182	0.032109	0.049828	-0.019452
+1.022373	-0.270527	-0.423746	9.817970	0.031043	0.049562	-0.020518
+1.023369	-0.244192	-0.426140	9.789242	0.029977	0.050228	-0.021051
+1.024369	-0.193917	-0.409381	9.839517	0.030243	0.048896	-0.020651
+1.025374	-0.217858	-0.375865	9.715026	0.030776	0.047564	-0.020518
+1.026369	-0.244192	-0.416563	9.748543	0.031309	0.049695	-0.018919
+1.027373	-0.253769	-0.445292	9.748543	0.031576	0.050628	-0.018919
+1.028369	-0.248980	-0.450080	9.659963	0.031176	0.049562	-0.020651
+1.029374	-0.268133	-0.392623	9.686298	0.030510	0.049962	-0.021583
+1.030373	-0.260951	-0.351924	9.767695	0.030643	0.049162	-0.021583
+1.031386	-0.248980	-0.390229	9.794030	0.032109	0.049429	-0.020518
+1.032450	-0.222646	-0.395017	9.817970	0.032775	0.050095	-0.019985
+1.033452	-0.270527	-0.409381	9.774877	0.034507	0.049429	-0.022649
+1.034446	-0.244192	-0.471626	9.834729	0.033708	0.048763	-0.021983
+1.035414	-0.232222	-0.433322	9.791636	0.033708	0.049695	-0.020518
+1.036392	-0.234616	-0.435716	9.794030	0.034374	0.051028	-0.021317
+1.037458	-0.277709	-0.459656	9.755725	0.034107	0.051294	-0.022916
+1.038450	-0.287285	-0.428534	9.779666	0.034374	0.050361	-0.022383
+1.039448	-0.213070	-0.442898	9.772483	0.035306	0.049429	-0.020784
+1.040450	-0.237010	-0.426140	9.825152	0.035972	0.049562	-0.019585
+1.041451	-0.227434	-0.411775	9.770089	0.036639	0.050361	-0.020118
+1.042451	-0.220252	-0.474021	9.861063	0.037305	0.050761	-0.020384
+1.043446	-0.256163	-0.423746	9.782060	0.036239	0.050228	-0.020384
+1.044450	-0.165189	-0.421352	9.784454	0.036639	0.050095	-0.019452
+1.045441	-0.184341	-0.392623	9.858669	0.036772	0.051161	-0.017720
+1.046375	-0.251375	-0.406987	9.889792	0.038237	0.049695	-0.017187
+1.047369	-0.265739	-0.440504	9.827546	0.039037	0.049562	-0.017587
+1.048367	-0.248980	-0.411775	9.738967	0.039436	0.050361	-0.020384
+1.049384	-0.258557	-0.397411	9.813182	0.038770	0.051028	-0.019185
+1.050401	-0.234616	-0.385441	9.841911	0.037971	0.049029	-0.018253
+1.051447	-0.248980	-0.471626	9.741361	0.038371	0.048230	-0.020384
+1.052447	-0.239404	-0.452474	9.770089	0.037704	0.050361	-0.019718
+1.053451	-0.229828	-0.351924	9.829940	0.037172	0.051694	-0.019851
+1.054450	-0.282497	-0.339954	9.803606	0.037704	0.050761	-0.019185
+1.055452	-0.260951	-0.351924	9.786848	0.037704	0.049828	-0.017187
+1.056426	-0.246586	-0.378259	9.717420	0.038504	0.049029	-0.018253
+1.057441	-0.304043	-0.387835	9.710238	0.038637	0.049962	-0.017853
+1.058451	-0.260951	-0.361500	9.741361	0.038904	0.050894	-0.018253
+1.059451	-0.213070	-0.363895	9.841911	0.039436	0.051694	-0.018919
+1.060450	-0.222646	-0.430928	9.779666	0.038770	0.051294	-0.020251
+1.061451	-0.239404	-0.411775	9.734179	0.039570	0.049828	-0.021317
+1.062452	-0.253769	-0.368683	9.774877	0.040369	0.049429	-0.019185
+1.063378	-0.258557	-0.361500	9.808394	0.039570	0.050361	-0.017587
+1.064372	-0.265739	-0.390229	9.899368	0.039436	0.050495	-0.018519
+1.065372	-0.246586	-0.452474	9.772483	0.038371	0.049695	-0.018919
+1.066371	-0.246586	-0.411775	9.688692	0.037704	0.049296	-0.020251
+1.067369	-0.227434	-0.349530	9.767695	0.036905	0.048496	-0.019319
+1.068371	-0.225040	-0.359106	9.820364	0.037038	0.049695	-0.019718
+1.069378	-0.304043	-0.471626	9.832334	0.038637	0.048363	-0.019851
+1.070374	-0.292073	-0.476415	9.820364	0.039436	0.047031	-0.017853
+1.071364	-0.229828	-0.428534	9.813182	0.039570	0.046764	-0.018386
+1.072369	-0.268133	-0.380653	9.794030	0.040236	0.048096	-0.019851
+1.073370	-0.253769	-0.385441	9.746149	0.038904	0.048363	-0.019185
+1.074374	-0.272921	-0.311226	9.743755	0.039303	0.047564	-0.019452
+1.075375	-0.222646	-0.351924	9.772483	0.039969	0.047564	-0.019052
+1.076380	-0.208282	-0.414169	9.817970	0.039170	0.049296	-0.018919
+1.077374	-0.268133	-0.409381	9.741361	0.037971	0.049695	-0.018119
+1.078373	-0.248980	-0.383047	9.782060	0.036372	0.048496	-0.018919
+1.079369	-0.251375	-0.411775	9.806000	0.036639	0.048363	-0.018119
+1.080370	-0.260951	-0.366289	9.851487	0.036772	0.047830	-0.018119
+1.081368	-0.239404	-0.404593	9.820364	0.037438	0.047697	-0.018519
+1.082372	-0.222646	-0.342348	9.813182	0.038104	0.047830	-0.020384
+1.083374	-0.253769	-0.318408	9.743755	0.037172	0.047963	-0.019985
+1.084408	-0.258557	-0.344742	9.717420	0.036905	0.047963	-0.018119
+1.085433	-0.284891	-0.385441	9.760513	0.038371	0.047031	-0.017054
+1.086447	-0.284891	-0.445292	9.784454	0.038904	0.047564	-0.018119
+1.087449	-0.272921	-0.430928	9.738967	0.038770	0.048763	-0.018386
+1.088451	-0.217858	-0.421352	9.719814	0.039436	0.049429	-0.016654
+1.089421	-0.253769	-0.433322	9.784454	0.040636	0.048896	-0.014789
+1.090452	-0.270527	-0.426140	9.827546	0.039969	0.048230	-0.015588
+1.091448	-0.256163	-0.395017	9.849093	0.040902	0.047697	-0.017720
+1.092455	-0.294467	-0.395017	9.825152	0.041435	0.047963	-0.017986
+1.093434	-0.260951	-0.380653	9.801212	0.041302	0.048230	-0.016920
+1.094425	-0.239404	-0.327984	9.717420	0.040103	0.050361	-0.016920
+1.095406	-0.232222	-0.335166	9.789242	0.039969	0.048763	-0.017587
+1.096394	-0.208282	-0.335166	9.796424	0.040236	0.046631	-0.017986
+1.097372	-0.208282	-0.351924	9.798818	0.040502	0.046498	-0.018253
+1.098378	-0.215464	-0.373471	9.806000	0.041035	0.046498	-0.015721
+1.099447	-0.229828	-0.387835	9.813182	0.041168	0.047430	-0.015322
+1.100451	-0.248980	-0.387835	9.794030	0.042767	0.047297	-0.016920
+1.101476	-0.232222	-0.402199	9.794030	0.042900	0.048230	-0.016387
+1.102444	-0.186735	-0.430928	9.731785	0.043167	0.048763	-0.017720
+1.103450	-0.239404	-0.416563	9.734179	0.043700	0.047697	-0.016654
+1.104418	-0.220252	-0.409381	9.885003	0.045032	0.046631	-0.015988
+1.105443	-0.275315	-0.450080	9.885003	0.045165	0.047297	-0.017720
+1.106452	-0.287285	-0.327984	9.602506	0.042900	0.048230	-0.016654
+1.107447	-0.263345	-0.356712	9.695874	0.041701	0.049029	-0.017320
+1.108452	-0.275315	-0.397411	9.820364	0.044100	0.048096	-0.017187
+1.109453	-0.220252	-0.418958	9.750937	0.046897	0.048363	-0.015455
+1.110449	-0.260951	-0.457262	9.772483	0.046897	0.049429	-0.017054
+1.111445	-0.292073	-0.416563	9.789242	0.046364	0.049296	-0.018519
+1.112451	-0.294467	-0.363895	9.817970	0.046498	0.048496	-0.018652
+1.113393	-0.280103	-0.361500	9.736573	0.045698	0.046631	-0.018253
+1.114385	-0.282497	-0.359106	9.715026	0.046764	0.047164	-0.018253
+1.115371	-0.246586	-0.361500	9.794030	0.047031	0.049429	-0.016787
+1.116431	-0.253769	-0.347136	9.765301	0.047297	0.049562	-0.016521
+1.117455	-0.277709	-0.380653	9.796424	0.046098	0.048763	-0.017453
+1.118377	-0.320802	-0.426140	9.808394	0.045698	0.047564	-0.017054
+1.119364	-0.239404	-0.392623	9.731785	0.046498	0.047031	-0.016387
+1.120373	-0.220252	-0.371077	9.801212	0.046631	0.048096	-0.017320
+1.121374	-0.275315	-0.409381	9.861063	0.047031	0.048230	-0.017453
+1.122373	-0.289679	-0.354318	9.791636	0.046498	0.048230	-0.017187
+1.123368	-0.258557	-0.368683	9.703056	0.043833	0.048363	-0.018519
+1.124373	-0.203494	-0.366289	9.753331	0.042767	0.049695	-0.017986
+1.125374	-0.208282	-0.416563	9.801212	0.041568	0.050361	-0.016920
+1.126373	-0.246586	-0.347136	9.712632	0.040236	0.048496	-0.017187
+1.127374	-0.203494	-0.387835	9.777271	0.041302	0.049029	-0.017320
+1.128358	-0.189129	-0.402199	9.827546	0.041968	0.049695	-0.019718
+1.129375	-0.160401	-0.368683	9.820364	0.041168	0.050095	-0.018652
+1.130373	-0.280103	-0.426140	9.782060	0.039703	0.050095	-0.019319
+1.131368	-0.227434	-0.423746	9.834729	0.039436	0.049296	-0.018519
+1.132393	-0.270527	-0.347136	9.731785	0.040502	0.049562	-0.017853
+1.133399	-0.232222	-0.251375	9.712632	0.041035	0.049162	-0.020651
+1.134398	-0.248980	-0.318408	9.748543	0.041435	0.050095	-0.020518
+1.135398	-0.263345	-0.409381	9.806000	0.043034	0.050228	-0.020251
+1.136379	-0.265739	-0.339954	9.767695	0.041568	0.050761	-0.019052
+1.137451	-0.316014	-0.335166	9.609688	0.037971	0.049828	-0.018253
+1.138449	-0.275315	-0.380653	9.760513	0.038371	0.050095	-0.017187
+1.139405	-0.234616	-0.406987	9.880215	0.039836	0.051028	-0.019585
+1.140449	-0.237010	-0.459656	9.851487	0.040103	0.050495	-0.021317
+1.141432	-0.263345	-0.397411	9.758119	0.040769	0.049828	-0.020651
+1.142419	-0.196312	-0.462050	9.736573	0.041168	0.051161	-0.021051
+1.143453	-0.241798	-0.423746	9.803606	0.041968	0.050495	-0.021051
+1.144449	-0.292073	-0.409381	9.724603	0.040769	0.048496	-0.019851
+1.145452	-0.213070	-0.342348	9.750937	0.040636	0.050228	-0.019718
+1.146388	-0.217858	-0.433322	9.755725	0.041435	0.051161	-0.019052
+1.147373	-0.272921	-0.397411	9.700662	0.042101	0.049162	-0.018919
+1.148367	-0.263345	-0.339954	9.710238	0.042101	0.047697	-0.019052
+1.149448	-0.210676	-0.421352	9.803606	0.041168	0.047963	-0.018119
+1.150444	-0.256163	-0.440504	9.853881	0.040502	0.049029	-0.018253
+1.151449	-0.292073	-0.342348	9.846699	0.041035	0.048496	-0.019985
+1.152434	-0.325590	-0.395017	9.861063	0.042767	0.048096	-0.020384
+1.153432	-0.304043	-0.363895	9.806000	0.043300	0.047697	-0.018786
+1.154453	-0.246586	-0.347136	9.806000	0.042900	0.048096	-0.019851
+1.155451	-0.260951	-0.406987	9.791636	0.041835	0.048096	-0.019185
+1.156450	-0.248980	-0.325590	9.676722	0.041835	0.047697	-0.019052
+1.157451	-0.284891	-0.342348	9.731785	0.041035	0.045565	-0.017986
+1.158450	-0.313620	-0.330378	9.813182	0.040502	0.045698	-0.017187
+1.159445	-0.229828	-0.399805	9.832334	0.041968	0.045565	-0.016787
+1.160449	-0.260951	-0.363895	9.832334	0.043167	0.045299	-0.017320
+1.161431	-0.325590	-0.387835	9.719814	0.044632	0.044499	-0.016387
+1.162383	-0.318408	-0.416563	9.772483	0.044233	0.044499	-0.018253
+1.163371	-0.308832	-0.361500	9.794030	0.044499	0.045565	-0.017587
+1.164373	-0.246586	-0.351924	9.743755	0.045299	0.045965	-0.016254
+1.165372	-0.234616	-0.387835	9.719814	0.044766	0.046897	-0.016254
+1.166373	-0.284891	-0.390229	9.688692	0.044632	0.047164	-0.017587
+1.167373	-0.265739	-0.366289	9.724603	0.046364	0.046631	-0.016920
+1.168368	-0.253769	-0.392623	9.758119	0.046231	0.045432	-0.016121
+1.169374	-0.296861	-0.349530	9.743755	0.043433	0.044766	-0.014922
+1.170373	-0.268133	-0.332772	9.688692	0.042368	0.045032	-0.014389
+1.171370	-0.284891	-0.433322	9.806000	0.045432	0.045965	-0.014922
+1.172369	-0.270527	-0.411775	9.832334	0.047031	0.046364	-0.013456
+1.173374	-0.244192	-0.399805	9.911338	0.047297	0.047297	-0.013190
+1.174363	-0.215464	-0.344742	9.827546	0.049162	0.047697	-0.014922
+1.175368	-0.287285	-0.304043	9.655175	0.045965	0.045832	-0.015188
+1.176373	-0.222646	-0.229828	9.607294	0.042634	0.045698	-0.013989
+1.177373	-0.301649	-0.430928	9.964007	0.045299	0.048496	-0.009992
+1.178373	-0.234616	-0.610481	10.193835	0.056090	0.051427	-0.007727
+1.179360	-0.110126	-0.332772	9.817970	0.053159	0.049828	-0.009726
+1.180369	-0.256163	-0.112520	9.193125	0.041968	0.045565	-0.011191
+1.181362	-0.471626	-0.356712	9.774877	0.039969	0.044499	-0.010126
+1.182387	0.016758	-0.301649	9.762907	0.037704	0.048763	-0.013590
+1.183448	-0.071821	-0.196312	9.401407	0.034640	0.047430	-0.016387
+1.184453	-0.330378	-0.162795	9.683904	0.028645	0.044632	-0.018253
+1.185452	-0.244192	-0.368683	9.592930	0.028645	0.042634	-0.015322
+1.186451	-0.371077	-0.490779	10.131590	0.033441	0.042234	-0.013590
+1.187433	-0.162795	-0.454868	9.846699	0.034107	0.043567	-0.015322
+1.188412	-0.055063	-0.263345	9.578566	0.030110	0.043567	-0.016387
+1.189397	-0.337560	-0.450080	9.868245	0.031975	0.041835	-0.014789
+1.190438	-0.349530	-0.440504	9.815576	0.035706	0.040502	-0.014123
+1.191451	-0.275315	-0.438110	9.664751	0.035173	0.040236	-0.012923
+1.192390	-0.146037	-0.186735	9.528291	0.028112	0.041035	-0.017587
+1.193452	-0.229828	-0.248980	9.576172	0.023982	0.039037	-0.017853
+1.194447	-0.349530	-0.442898	9.817970	0.026380	0.037038	-0.017054
+1.195435	-0.265739	-0.474021	9.885003	0.028778	0.035040	-0.016521
+1.196375	-0.282497	-0.280103	9.856275	0.024115	0.032508	-0.016387
+1.197372	-0.165189	-0.119702	9.489986	0.018119	0.032775	-0.019185
+1.198372	-0.184341	-0.454868	9.571384	0.021450	0.037305	-0.019985
+1.199373	-0.225040	-0.600905	10.105255	0.031043	0.040103	-0.020518
+1.200369	-0.162795	-0.402199	9.896974	0.032242	0.037971	-0.019585
+1.201374	-0.234616	-0.198706	9.442105	0.026646	0.038104	-0.016654
+1.202369	-0.239404	-0.320802	9.604900	0.023715	0.037571	-0.017720
+1.203405	-0.181947	-0.332772	9.734179	0.021583	0.035839	-0.019718
+1.204438	-0.325590	-0.284891	9.604900	0.017187	0.034374	-0.019985
+1.205459	-0.327984	-0.272921	9.600112	0.017187	0.036505	-0.017986
+1.206402	-0.179553	-0.418958	9.734179	0.020917	0.039570	-0.019319
+1.207445	-0.220252	-0.390229	9.724603	0.022516	0.030776	-0.022783
+1.208449	-0.361500	-0.055063	9.489986	0.007461	0.028778	-0.022649
+1.209451	-0.253769	-0.045487	9.334374	-0.000533	0.031576	-0.018119
+1.210449	-0.280103	-0.667938	9.992735	0.018519	0.039570	-0.019185
+1.211446	-0.033517	-0.768488	10.382964	0.036772	0.041968	-0.022916
+1.212449	-0.287285	-0.268133	9.724603	0.032908	0.040236	-0.023315
+1.213391	-0.375865	-0.184341	9.370284	0.021583	0.036905	-0.022649
+1.214363	-0.222646	-0.366289	9.647993	0.019319	0.037438	-0.022250
+1.215382	-0.162795	-0.454868	9.887397	0.022516	0.037971	-0.022783
+1.216402	-0.263345	-0.344742	9.853881	0.024914	0.039170	-0.020518
+1.217406	-0.316014	-0.296861	9.717420	0.023049	0.039436	-0.020917
+1.218452	-0.270527	-0.313620	9.703056	0.021317	0.039037	-0.022250
+1.219445	-0.280103	-0.311226	9.664751	0.018652	0.037038	-0.022516
+1.220447	-0.241798	-0.325590	9.552231	0.014789	0.035173	-0.023182
+1.221449	-0.284891	-0.294467	9.628841	0.011858	0.035972	-0.024115
+1.222452	-0.272921	-0.277709	9.643205	0.008926	0.035573	-0.021583
+1.223450	-0.270527	-0.268133	9.664751	0.004130	0.031709	-0.017986
+1.224433	-0.363895	-0.272921	9.691086	0.002798	0.029577	-0.017453
+1.225443	-0.313620	-0.538660	9.813182	0.013057	0.035306	-0.019185
+1.226451	-0.136460	-0.603299	10.076527	0.023182	0.042234	-0.019851
+1.227450	-0.201100	-0.402199	9.801212	0.023982	0.044366	-0.019452
+1.228446	-0.270527	-0.227434	9.578566	0.019985	0.042368	-0.018652
+1.229378	-0.272921	-0.191523	9.557020	0.014922	0.040769	-0.018119
+1.230377	-0.251375	-0.270527	9.681510	0.013057	0.041035	-0.019585
+1.231371	-0.246586	-0.371077	9.827546	0.016254	0.042234	-0.021850
+1.232458	-0.189129	-0.282497	9.786848	0.015322	0.041701	-0.020917
+1.233451	-0.213070	-0.251375	9.647993	0.011858	0.041035	-0.018786
+1.234450	-0.232222	-0.304043	9.643205	0.009859	0.042368	-0.019585
+1.235410	-0.263345	-0.335166	9.717420	0.010658	0.043300	-0.020651
+1.236384	-0.289679	-0.399805	9.817970	0.012391	0.041968	-0.019585
+1.237426	-0.220252	-0.399805	9.851487	0.013590	0.041701	-0.019452
+1.238451	-0.229828	-0.359106	9.794030	0.016387	0.042234	-0.020651
+1.239450	-0.237010	-0.387835	9.791636	0.018253	0.043433	-0.021850
+1.240451	-0.201100	-0.406987	9.817970	0.018786	0.044366	-0.021583
+1.241452	-0.258557	-0.378259	9.770089	0.017986	0.044499	-0.020384
+1.242446	-0.169977	-0.421352	9.841911	0.018119	0.044766	-0.019585
+1.243451	-0.208282	-0.383047	9.856275	0.018652	0.044233	-0.019452
+1.244448	-0.217858	-0.304043	9.782060	0.019052	0.042234	-0.018919
+1.245444	-0.210676	-0.313620	9.753331	0.018919	0.043567	-0.019851
+1.246359	-0.260951	-0.418958	9.796424	0.020118	0.044366	-0.020651
+1.247349	-0.248980	-0.457262	9.760513	0.021317	0.044632	-0.021051
+1.248359	-0.213070	-0.433322	9.794030	0.022783	0.045299	-0.020784
+1.249449	-0.234616	-0.385441	9.736573	0.024515	0.045565	-0.019851
+1.250450	-0.248980	-0.337560	9.743755	0.023582	0.045032	-0.020784
+1.251436	-0.205888	-0.383047	9.691086	0.023315	0.044766	-0.020518
+1.252408	-0.201100	-0.349530	9.724603	0.024914	0.045165	-0.021184
+1.253449	-0.227434	-0.375865	9.796424	0.025980	0.045032	-0.021184
+1.254436	-0.289679	-0.356712	9.829940	0.025980	0.043833	-0.019718
+1.255447	-0.251375	-0.308832	9.784454	0.026779	0.043567	-0.018786
+1.256463	-0.270527	-0.371077	9.784454	0.027579	0.045698	-0.017853
+1.257429	-0.234616	-0.380653	9.784454	0.027712	0.047430	-0.016521
+1.258452	-0.210676	-0.380653	9.844305	0.028645	0.047164	-0.018519
+1.259451	-0.256163	-0.327984	9.801212	0.029178	0.046498	-0.018519
+1.260439	-0.217858	-0.337560	9.724603	0.029577	0.045432	-0.018919
+1.261410	-0.198706	-0.390229	9.669540	0.028378	0.044766	-0.019452
+1.262383	-0.237010	-0.380653	9.655175	0.028778	0.044499	-0.019319
+1.263378	-0.220252	-0.411775	9.765301	0.029711	0.045432	-0.019585
+1.264355	-0.248980	-0.323196	9.873033	0.027845	0.045165	-0.020651
+1.265352	-0.253769	-0.375865	9.832334	0.029178	0.045299	-0.021983
+1.266452	-0.146037	-0.390229	9.789242	0.030910	0.046231	-0.022116
+1.267453	-0.143643	-0.349530	9.767695	0.030377	0.045965	-0.023049
+1.268419	-0.169977	-0.351924	9.760513	0.030110	0.045565	-0.023982
+1.269447	-0.222646	-0.397411	9.724603	0.029311	0.045165	-0.023982
+1.270450	-0.258557	-0.354318	9.662357	0.029577	0.043833	-0.022516
+1.271450	-0.232222	-0.373471	9.734179	0.031043	0.043966	-0.023182
+1.272450	-0.234616	-0.339954	9.940066	0.030776	0.045032	-0.022250
+1.273447	-0.246586	-0.342348	9.832334	0.030776	0.045432	-0.022250
+1.274451	-0.222646	-0.409381	9.863457	0.032242	0.044233	-0.023449
+1.275453	-0.222646	-0.428534	9.875427	0.033441	0.043833	-0.024914
+1.276447	-0.277709	-0.354318	9.662357	0.033441	0.043700	-0.025314
+1.277451	-0.244192	-0.380653	9.686298	0.033574	0.043966	-0.026913
+1.278420	-0.217858	-0.411775	9.849093	0.035173	0.044899	-0.025181
+1.279377	-0.174765	-0.402199	9.853881	0.035573	0.046631	-0.024648
+1.280360	-0.220252	-0.359106	9.767695	0.035706	0.046764	-0.025047
+1.281352	-0.222646	-0.373471	9.736573	0.035440	0.045965	-0.025447
+1.282367	-0.253769	-0.368683	9.679116	0.036772	0.044766	-0.026380
+1.283374	-0.280103	-0.390229	9.770089	0.038371	0.045299	-0.025714
+1.284368	-0.263345	-0.406987	9.767695	0.039303	0.045565	-0.025714
+1.285374	-0.268133	-0.371077	9.762907	0.040769	0.044366	-0.026380
+1.286373	-0.241798	-0.368683	9.724603	0.042101	0.045565	-0.026779
+1.287368	-0.253769	-0.361500	9.841911	0.043167	0.048230	-0.027312
+1.288369	-0.268133	-0.356712	9.825152	0.043700	0.048496	-0.025847
+1.289369	-0.246586	-0.339954	9.772483	0.043700	0.047697	-0.025580
+1.290373	-0.292073	-0.316014	9.767695	0.040769	0.046897	-0.026913
+1.291373	-0.277709	-0.354318	9.746149	0.040369	0.046631	-0.027046
+1.292369	-0.260951	-0.416563	9.772483	0.042101	0.043300	-0.027446
+1.293369	-0.179553	-0.402199	9.734179	0.042101	0.040103	-0.029311
+1.294373	-0.227434	-0.452474	9.858669	0.041701	0.040769	-0.031176
+1.295373	-0.203494	-0.474021	9.885003	0.044233	0.041568	-0.034107
+1.296374	-0.155613	-0.418958	9.784454	0.046364	0.041168	-0.034507
+1.297422	-0.251375	-0.304043	9.712632	0.044233	0.039570	-0.032375
+1.298419	-0.337560	-0.296861	9.616871	0.040636	0.037038	-0.030776
+1.299407	-0.351924	-0.327984	9.671934	0.037704	0.037438	-0.029444
+1.300413	-0.265739	-0.299255	9.748543	0.036639	0.037971	-0.028245
+1.301359	-0.256163	-0.294467	9.688692	0.034640	0.038904	-0.027979
+1.302368	-0.227434	-0.342348	9.729391	0.034107	0.038637	-0.027845
+1.303373	-0.196312	-0.416563	9.760513	0.036505	0.037971	-0.027579
+1.304373	-0.220252	-0.344742	9.777271	0.035706	0.039037	-0.026513
+1.305369	-0.260951	-0.306437	9.710238	0.035573	0.039703	-0.027312
+1.306368	-0.225040	-0.318408	9.741361	0.034240	0.039037	-0.027579
+1.307373	-0.253769	-0.284891	9.734179	0.032109	0.039170	-0.027312
+1.308373	-0.284891	-0.308832	9.698268	0.029711	0.038770	-0.026380
+1.309374	-0.294467	-0.193917	9.645599	0.023315	0.036106	-0.023982
+1.310368	-0.366289	-0.193917	9.712632	0.020784	0.032109	-0.021583
+1.311370	-0.193917	-0.418958	9.803606	0.021850	0.034240	-0.021717
+1.312373	-0.191523	-0.411775	9.758119	0.025314	0.037971	-0.022250
+1.313375	-0.260951	-0.440504	9.779666	0.027712	0.039037	-0.022649
+1.314371	-0.251375	-0.428534	9.916126	0.028911	0.037838	-0.023315
+1.315400	-0.304043	-0.354318	9.808394	0.027712	0.033841	-0.020917
+1.316420	-0.284891	-0.440504	9.813182	0.030776	0.032775	-0.019319
+1.317452	-0.148431	-0.469232	9.784454	0.034640	0.036505	-0.018786
+1.318450	-0.251375	-0.299255	9.844305	0.032109	0.035440	-0.016920
+1.319410	-0.495567	-0.179553	9.707844	0.026913	0.029711	-0.013323
+1.320452	-0.373471	-0.354318	9.810788	0.029711	0.028778	-0.013323
+1.321451	-0.081397	-0.557812	9.935278	0.040502	0.033574	-0.016121
+1.322451	-0.122096	-0.478809	9.995129	0.046231	0.036106	-0.016121
+1.323449	-0.354318	-0.356712	9.899368	0.047164	0.033708	-0.013057
+1.324431	-0.325590	-0.339954	9.846699	0.046498	0.029711	-0.010925
+1.325400	-0.246586	-0.615269	9.971189	0.054092	0.032642	-0.012923
+1.326448	-0.153219	-0.620057	10.078921	0.063152	0.036639	-0.017054
+1.327449	-0.263345	-0.330378	9.798818	0.064750	0.038237	-0.017054
+1.328451	-0.320802	-0.263345	9.573778	0.059954	0.038504	-0.012657
+1.329405	-0.313620	-0.308832	9.631235	0.057556	0.039436	-0.011058
+1.330373	-0.229828	-0.347136	9.755725	0.057423	0.040636	-0.010925
+1.331372	-0.251375	-0.337560	9.770089	0.058089	0.040636	-0.010126
+1.332359	-0.287285	-0.342348	9.729391	0.059288	0.039303	-0.009459
+1.333357	-0.253769	-0.313620	9.734179	0.061420	0.038371	-0.007994
+1.334356	-0.232222	-0.344742	9.784454	0.061553	0.039703	-0.007727
+1.335356	-0.237010	-0.368683	9.743755	0.061020	0.039703	-0.008394
+1.336449	-0.244192	-0.366289	9.691086	0.061020	0.040902	-0.006395
+1.337424	-0.225040	-0.366289	9.767695	0.061020	0.043300	-0.005063
+1.338396	-0.148431	-0.361500	9.712632	0.062086	0.044366	-0.005729
+1.339445	-0.246586	-0.306437	9.655175	0.060354	0.043034	-0.005995
+1.340451	-0.225040	-0.248980	9.523503	0.055957	0.042900	-0.005596
+1.341452	-0.222646	-0.256163	9.633629	0.054225	0.044233	-0.005596
+1.342449	-0.117308	-0.366289	9.712632	0.055158	0.043433	-0.007194
+1.343451	-0.270527	-0.373471	9.777271	0.055957	0.042634	-0.007328
+1.344449	-0.208282	-0.354318	9.820364	0.056490	0.042634	-0.005596
+1.345446	-0.215464	-0.366289	9.834729	0.056490	0.042368	-0.004796
+1.346391	-0.296861	-0.320802	9.731785	0.053426	0.039037	-0.007061
+1.347384	-0.198706	-0.244192	9.693480	0.048763	0.035839	-0.006129
+1.348371	-0.114914	-0.071821	9.803606	0.013323	0.006528	0.002531
+1.349349	-1.781168	3.586276	8.841201	-0.117776	-0.102455	0.017587
+1.350357	-2.678934	-0.890584	5.276471	-0.103254	-0.026513	0.039303
+1.351351	3.172107	-3.028464	13.521555	0.039170	0.053159	0.005063
+1.352387	1.460366	-2.032542	12.800948	0.112980	0.072078	-0.027845
+1.353375	-1.113230	0.478809	8.625737	0.073277	0.049296	-0.019052
+1.354370	-0.964799	0.299255	8.747833	0.029577	0.033041	-0.000666
+1.355371	0.079003	-0.550630	10.028646	0.029844	0.037438	0.000933
+1.356371	0.153219	-0.351924	9.784454	0.037305	0.040902	-0.005596
+1.357371	-0.280103	-0.244192	9.595324	0.041035	0.036505	-0.007461
+1.358372	-0.280103	-0.514719	9.918520	0.046498	0.035839	-0.007328
+1.359372	-0.071821	-0.373471	9.782060	0.044366	0.038371	-0.006662
+1.360448	-0.174765	-0.241798	9.628841	0.039836	0.038104	-0.007061
+1.361431	-0.203494	-0.373471	9.889792	0.042767	0.039303	-0.009193
+1.362392	-0.169977	-0.323196	9.645599	0.044100	0.041035	-0.010392
+1.363382	-0.268133	-0.208282	9.461258	0.039037	0.039703	-0.009726
+1.364373	-0.275315	-0.251375	9.765301	0.037571	0.036772	-0.008793
+1.365372	-0.253769	-0.411775	9.880215	0.042101	0.033308	-0.011191
+1.366386	-0.141249	-0.349530	9.825152	0.045432	0.034907	-0.012790
+1.367384	-0.086186	-0.323196	9.712632	0.046364	0.037172	-0.013190
+1.368391	-0.165189	-0.409381	9.863457	0.049562	0.039703	-0.014389
+1.369391	-0.153219	-0.368683	9.851487	0.050761	0.040103	-0.015721
+1.370450	-0.263345	-0.263345	9.715026	0.047031	0.035573	-0.015721
+1.371446	-0.294467	-0.292073	9.681510	0.044766	0.032775	-0.014655
+1.372449	-0.143643	-0.483597	9.954431	0.048629	0.032242	-0.014922
+1.373419	-0.110126	-0.471626	10.016676	0.052360	0.032375	-0.017720
+1.374433	-0.191523	-0.327984	9.791636	0.050095	0.029977	-0.018119
+1.375451	-0.366289	-0.270527	9.722208	0.048230	0.022783	-0.017587
+1.376450	-0.229828	-0.325590	9.882609	0.051427	0.016787	-0.017853
+1.377453	-0.205888	-0.402199	10.059769	0.055291	0.010525	-0.019851
+1.378450	-0.251375	-0.232222	9.908944	0.052760	0.005063	-0.020251
+1.379369	-0.354318	-0.114914	9.707844	0.045565	-0.003064	-0.018519
+1.380374	-0.308832	-0.337560	9.846699	0.044366	-0.011858	-0.016254
+1.381372	-0.277709	-0.416563	10.052586	0.051294	-0.015055	-0.016521
+1.382447	-0.177159	-0.411775	9.987947	0.058222	-0.015188	-0.015721
+1.383405	-0.186735	-0.351924	9.849093	0.059688	-0.018386	-0.015455
+1.384404	-0.263345	-0.256163	9.825152	0.057289	-0.026380	-0.015988
+1.385382	-0.402199	-0.275315	9.923308	0.054092	-0.035839	-0.014655
+1.386407	-0.304043	-0.363895	9.954431	0.054625	-0.042501	-0.012923
+1.387396	-0.287285	-0.308832	9.975977	0.057423	-0.046364	-0.013190
+1.388450	-0.308832	-0.248980	9.889792	0.056490	-0.053559	-0.012124
+1.389410	-0.263345	-0.414169	9.913732	0.062219	-0.052760	-0.012657
+1.390450	0.000000	-0.670332	9.846699	0.075542	-0.036905	-0.015855
+1.391450	0.011970	-0.344742	9.844305	0.080072	-0.030377	-0.021051
+1.392450	-0.337560	-0.158007	9.683904	0.074876	-0.036106	-0.019718
+1.393451	-0.351924	-0.232222	9.734179	0.068081	-0.051294	-0.014256
+1.394451	-0.311226	-0.265739	10.047798	0.059155	-0.080205	-0.013590
+1.395423	-0.471626	-0.045487	10.665461	0.041035	-0.139360	-0.009992
+1.396393	-0.768488	0.672726	11.249608	-0.003730	-0.262066	0.000933
+1.397367	-1.446002	0.306437	11.019780	-0.012923	-0.334144	0.002798
+1.398367	-0.105338	-1.541764	8.913022	0.042234	-0.226893	-0.002531
+1.399444	0.885796	-0.948041	8.321693	0.082070	-0.091397	-0.011858
+1.400452	0.457262	-0.248980	8.345634	0.078207	-0.031309	-0.015055
+1.401452	0.019152	-0.155613	9.245794	0.062086	-0.041435	-0.015721
+1.402447	-0.359106	-0.167583	10.167500	0.053692	-0.077274	-0.012923
+1.403452	-0.459656	-0.272921	9.676722	0.053825	-0.088599	-0.005462
+1.404450	-0.296861	-0.260951	9.370284	0.054225	-0.076608	-0.001332
+1.405450	-0.014364	-0.220252	9.497168	0.052493	-0.062752	-0.003730
+1.406417	-0.038305	-0.366289	9.614477	0.053292	-0.049296	-0.006528
+1.407447	-0.124490	-0.301649	9.707844	0.052093	-0.049962	-0.007061
+1.408451	-0.153219	-0.304043	9.853881	0.053559	-0.052093	-0.005729
+1.409451	-0.093368	-0.306437	9.688692	0.053559	-0.051427	-0.005596
+1.410445	-0.153219	-0.270527	9.715026	0.054092	-0.049429	-0.006129
+1.411451	-0.134066	-0.325590	9.782060	0.056357	-0.041568	-0.005329
+1.412447	-0.143643	-0.373471	9.794030	0.056890	-0.038770	-0.004796
+1.413431	-0.126884	-0.270527	9.822758	0.055291	-0.045165	-0.006262
+1.414412	-0.201100	-0.260951	9.841911	0.053292	-0.051427	-0.004530
+1.415418	-0.201100	-0.359106	9.731785	0.052227	-0.053026	-0.003597
+1.416411	-0.134066	-0.325590	9.705450	0.053026	-0.052360	-0.004263
+1.417419	-0.074215	-0.342348	9.686298	0.055291	-0.046498	-0.005462
+1.418417	-0.033517	-0.325590	9.657569	0.055291	-0.041168	-0.008260
+1.419411	-0.069427	-0.335166	9.703056	0.056090	-0.040636	-0.009859
+1.420443	-0.076609	-0.306437	9.978371	0.061153	-0.047697	-0.006262
+1.421513	-0.287285	-0.021546	10.600822	0.126170	-0.065150	0.024115
+1.422510	-0.775670	1.091684	13.976423	0.245545	-0.156413	0.063285
+1.423510	-0.756518	-1.103654	14.931646	0.294574	-0.287513	0.063951
+1.424509	-0.478809	-1.522611	12.429871	0.260734	-0.388103	0.041168
+1.425465	0.122096	-0.816369	9.540261	0.160277	-0.420211	0.000266
+1.426503	0.622451	-0.962405	7.256344	0.076608	-0.370649	-0.033841
+1.427511	0.447686	0.488385	7.031304	0.047564	-0.285381	-0.034640
+1.428510	-0.239404	0.339954	7.615451	0.061819	-0.198781	-0.017453
+1.429444	-0.179553	-0.134066	8.415061	0.086067	-0.141758	-0.004930
+1.430426	0.064639	-0.263345	9.111728	0.100057	-0.110182	-0.003464
+1.431420	0.071821	-0.270527	8.903446	0.096193	-0.081271	-0.005596
+1.432418	0.095762	-0.308832	8.807684	0.083669	-0.054758	-0.009193
+1.433383	0.079003	-0.282497	9.173973	0.076741	-0.041435	-0.010525
+1.434384	-0.052669	-0.282497	9.451682	0.075142	-0.030643	-0.011458
+1.435379	-0.107732	-0.349530	9.631235	0.076342	-0.027712	-0.008660
+1.436438	-0.088580	-0.251375	9.794030	0.077407	-0.027312	-0.007461
+1.437443	-0.052669	-0.296861	9.774877	0.080338	-0.025181	-0.009060
+1.438476	-0.062245	-0.280103	9.760513	0.083403	-0.020251	-0.009326
+1.439477	-0.007182	-0.268133	9.681510	0.082737	-0.016920	-0.008793
+1.440476	-0.031123	-0.248980	9.741361	0.080871	-0.017054	-0.010658
+1.441478	-0.074215	-0.277709	9.729391	0.082603	-0.018386	-0.011191
+1.442477	-0.090974	-0.248980	9.707844	0.085135	-0.018386	-0.007994
+1.443429	-0.079003	-0.284891	9.760513	0.085534	-0.018519	-0.007861
+1.444435	-0.148431	-0.304043	9.794030	0.086067	-0.022783	-0.007461
+1.445456	-0.126884	-0.253769	9.849093	0.087799	-0.028112	-0.006528
+1.446396	-0.198706	-0.198706	9.997523	0.088998	-0.039570	-0.005596
+1.447385	-0.239404	-0.141249	10.174683	0.088732	-0.056890	-0.004530
+1.448383	-0.292073	-0.162795	10.258474	0.089132	-0.075142	-0.000933
+1.449402	-0.277709	-0.198706	10.215381	0.091530	-0.093928	0.000533
+1.450398	-0.110126	-0.241798	10.210593	0.093528	-0.110982	0.000000
+1.451403	-0.146037	-0.299255	10.315931	0.096326	-0.127502	-0.000133
+1.452502	-0.098156	-0.292073	10.287203	0.096459	-0.147887	0.001732
+1.453503	-0.131672	-0.251375	10.452392	0.094461	-0.180528	0.000000
+1.454502	-0.292073	-0.181947	10.818680	0.091930	-0.226493	0.000000
+1.455502	-0.354318	-0.198706	11.134694	0.090198	-0.286314	-0.001332
+1.456444	-0.366289	-0.263345	11.649413	0.084868	-0.374113	-0.005862
+1.457506	-0.371077	-0.387835	12.511269	0.075809	-0.500017	-0.017320
+1.458468	-0.141249	-0.608087	13.952482	0.056090	-0.709723	-0.036106
+1.459500	0.524295	-0.986346	17.641703	0.091796	-1.027080	-0.087133
+1.460505	2.164215	-1.062955	14.677877	0.569697	-0.755954	-0.133498
+1.461461	3.919048	-0.421352	13.705896	1.524299	-0.165340	-0.157613
+1.462440	1.252084	-3.366024	31.361963	2.287847	0.019185	-0.130034
+1.463412	-1.546552	-11.240032	14.170340	1.725611	-0.092063	-0.102455
+1.464404	-4.409827	0.335166	-13.200753	0.721181	-0.252207	-0.054092
+1.465401	-1.362210	12.118646	-11.503376	-0.026380	-0.383573	-0.014389
+1.466398	1.424456	2.389255	5.487146	-0.141758	-0.455518	-0.029711
+1.467411	-0.368683	-1.424456	14.819126	0.016254	-0.642841	-0.067948
+1.468417	-0.782852	-0.782852	11.216091	0.208640	-0.508810	-0.041568
+1.469359	1.453184	-0.385441	2.693298	0.261666	-0.147087	0.001732
+1.470358	-0.064639	1.424456	5.853435	0.181194	-0.020251	0.016920
+1.471400	0.062245	1.496277	6.820628	0.087266	-0.033708	0.012257
+1.472451	0.277709	-0.155613	9.147638	0.068614	-0.059821	0.003198
+1.473450	0.287285	-0.794822	10.342266	0.105119	-0.061953	0.001865
+1.474451	0.071821	-0.074215	9.705450	0.132432	-0.052493	0.004930
+1.475451	-0.107732	0.026334	9.885003	0.146688	-0.050361	0.005596
+1.476462	0.246586	-0.421352	10.835438	0.204243	-0.042900	0.000133
+1.477431	0.871432	-0.071821	12.927832	0.460047	-0.016920	-0.038770
+1.478449	2.164215	1.829049	23.827910	1.407322	0.158545	-0.013323
+1.479360	1.553734	1.486701	39.222803	1.919196	0.189988	0.090997
+1.480368	-3.842439	-16.265128	13.950088	1.232655	-0.040902	0.044100
+1.481361	-2.327010	7.131854	-5.151980	0.569963	-0.451387	-0.039836
+1.482388	2.796242	4.797662	-1.216174	-0.034107	-0.713453	-0.142957
+1.483401	2.868063	-1.929599	10.694190	-0.063951	-0.699997	-0.293242
+1.484400	6.155084	2.408407	23.705813	0.420211	-0.083403	-0.407554
+1.485401	5.721763	8.065531	30.497713	0.664691	0.991107	-0.086067
+1.486403	-1.881718	-0.055063	33.102432	0.147620	1.201746	-0.011858
+1.487399	-4.510377	-9.789242	5.599667	-0.053959	0.813510	-0.088599
+1.488401	-2.291099	7.165371	5.381809	-0.241149	0.465510	-0.241282
+1.489399	1.091684	-6.700926	23.993099	-0.532259	0.038637	-0.384505
+1.490410	0.244192	-7.110308	10.449998	-0.455251	-0.192253	-0.438997
+1.491408	1.302359	5.317169	-10.088497	-0.031975	0.352796	-0.220498
+1.492406	0.696667	12.472964	-5.022702	-0.175466	0.917963	-0.140426
+1.493391	-8.640101	2.475440	35.166097	-0.624055	0.211038	0.076075
+1.494399	-1.017468	-16.190913	27.806809	-0.516271	-0.552510	-0.007328
+1.495449	5.084947	-7.500537	6.404065	-0.173600	-0.377844	-0.226760
+1.496369	3.038041	3.241534	9.401407	-0.262732	0.226360	-0.636179
+1.497365	-4.816814	1.647102	13.016412	-0.562103	0.476835	-0.847217
+1.498370	-2.499381	6.990605	8.793320	-0.656830	0.375312	-0.824168
+1.499444	-5.116070	-4.163241	11.067661	-0.768345	0.500283	-0.720914
+1.500448	-3.241534	-0.854673	11.891211	-0.728508	0.653632	-0.667355
+1.501439	2.494593	0.146037	10.562518	-0.611531	0.583286	-0.634181
+1.502468	5.281259	0.043093	9.609688	-0.557040	0.417280	-0.621657
+1.503449	5.590090	0.718213	9.901762	-0.563168	0.342804	-0.612597
+1.504448	4.785692	0.323196	9.485198	-0.557839	0.312028	-0.583420
+1.505450	3.251110	-0.368683	9.442105	-0.518003	0.237418	-0.517070
+1.506445	1.970297	-1.197021	9.604900	-0.460047	0.150418	-0.439130
+1.507449	1.362210	-1.601615	9.964007	-0.406222	0.103787	-0.381574
+1.508400	1.010286	-1.639919	10.375782	-0.361456	0.093129	-0.347734
+1.509451	0.703849	-1.115624	10.634339	-0.316424	0.059021	-0.320155
+1.510455	0.433322	-0.948041	10.521819	-0.277787	-0.015855	-0.289911
+1.511410	0.500355	-0.689484	10.538577	-0.247677	-0.064217	-0.265397
+1.512442	1.244902	-0.356712	10.519425	-0.231023	-0.068614	-0.264864
+1.513372	2.010996	0.057457	10.691796	-0.215568	-0.022250	-0.269527
+1.514366	0.969587	0.000000	11.156240	-0.196116	-0.008793	-0.243946
+1.515386	-0.035911	-0.059851	11.113147	-0.178930	-0.036372	-0.208773
+1.516394	-0.186735	-0.102944	10.900078	-0.166273	-0.077807	-0.169470
+1.517516	-0.699061	-0.047881	10.789952	-0.161743	-0.119242	-0.132165
+1.518511	-0.756518	-0.023940	10.576882	-0.164141	-0.158412	-0.108583
+1.519513	-0.567388	0.057457	10.579276	-0.170136	-0.198914	-0.087400
+1.520514	-0.553024	0.083792	10.433239	-0.176931	-0.237818	-0.071145
+1.521449	-0.155613	0.122096	10.217775	-0.187190	-0.257003	-0.071545
+1.522514	0.363895	0.119702	10.308749	-0.196516	-0.251674	-0.083536
+1.523511	0.737365	0.122096	10.512243	-0.200779	-0.228225	-0.102988
+1.524510	0.914524	0.026334	10.581670	-0.199714	-0.202778	-0.122972
+1.525513	0.983952	-0.038305	10.689402	-0.191320	-0.179462	-0.139626
+1.526510	1.096472	-0.074215	10.792346	-0.174400	-0.160943	-0.153749
+1.527511	0.986346	-0.143643	10.871349	-0.151084	-0.151750	-0.161343
+1.528511	0.845097	-0.268133	10.914442	-0.126570	-0.154282	-0.164008
+1.529466	0.708637	-0.292073	10.914442	-0.105652	-0.166273	-0.161077
+1.530417	0.694272	-0.222646	10.799528	-0.086334	-0.181727	-0.161210
+1.531440	0.612875	-0.234616	10.653491	-0.068481	-0.202378	-0.158279
+1.532439	0.658362	-0.179553	10.564912	-0.053959	-0.217167	-0.153216
+1.533440	0.713425	-0.074215	10.490696	-0.041835	-0.227026	-0.148553
+1.534439	0.624845	-0.033517	10.303961	-0.035306	-0.239683	-0.142691
+1.535437	0.545842	0.086186	10.270444	-0.031176	-0.248609	-0.134564
+1.536437	0.538660	0.126884	10.162712	-0.027845	-0.252074	-0.124571
+1.537399	0.474021	0.090974	10.201017	-0.023449	-0.254072	-0.111914
+1.538510	0.430928	0.217858	10.217775	-0.021450	-0.261799	-0.102455
+1.539511	0.392623	0.210676	10.172289	-0.019718	-0.270726	-0.089531
+1.540445	0.301649	0.174765	10.114832	-0.017453	-0.282450	-0.078340
+1.541510	0.335166	0.160401	10.021464	-0.013723	-0.290044	-0.070213
+1.542450	0.454868	0.193917	10.157924	-0.008793	-0.292709	-0.063685
+1.543451	0.426140	0.169977	10.145954	-0.003464	-0.295640	-0.058089
+1.544450	0.383047	0.181947	10.076527	0.002798	-0.301502	-0.055025
+1.545518	0.454868	0.150825	10.086103	0.008527	-0.308963	-0.050894
+1.546440	0.658362	0.141249	10.028646	0.018253	-0.311095	-0.051560
+1.547416	0.699061	0.098156	9.995129	0.031309	-0.309896	-0.049029
+1.548415	0.548236	0.074215	10.050192	0.047164	-0.317623	-0.043300
+1.549394	0.488385	0.081397	9.937672	0.063285	-0.333478	-0.038770
+1.550405	0.576964	0.174765	9.899368	0.079006	-0.346002	-0.039436
+1.551388	0.718213	0.189129	9.863457	0.094594	-0.349599	-0.039836
+1.552410	0.737365	0.172371	9.896974	0.112714	-0.353196	-0.038904
+1.553488	0.579358	0.136460	9.920914	0.133764	-0.362522	-0.036106
+1.554431	0.426140	0.114914	10.021464	0.154948	-0.375845	-0.032375
+1.555430	0.414169	0.148431	10.033434	0.171202	-0.394498	-0.029044
+1.556426	0.383047	0.069427	9.889792	0.186524	-0.411685	-0.027446
+1.557490	0.440504	0.083792	9.908944	0.199714	-0.422077	-0.025580
+1.558491	0.536266	0.169977	9.975977	0.210372	-0.426340	-0.024115
+1.559489	0.564994	0.169977	9.975977	0.219565	-0.427939	-0.021051
+1.560487	0.612875	0.095762	9.949643	0.230490	-0.425940	-0.016121
+1.561420	0.598511	0.100550	9.961613	0.241015	-0.426340	-0.011591
+1.562454	0.521901	0.045487	9.966401	0.250075	-0.431536	-0.004530
+1.563402	0.430928	-0.040699	9.875427	0.257802	-0.440729	0.003198
+1.564406	0.538660	-0.040699	9.820364	0.262599	-0.448856	0.008793
+1.565429	0.557812	-0.069427	9.779666	0.269793	-0.457116	0.014922
+1.566427	0.507537	-0.136460	9.681510	0.278054	-0.466443	0.023848
+1.567421	0.442898	-0.186735	9.647993	0.285515	-0.473504	0.031576
+1.568426	0.371077	-0.280103	9.659963	0.294308	-0.482164	0.041568
+1.569408	0.172371	-0.418958	9.604900	0.303101	-0.494288	0.049828
+1.570512	0.181947	-0.495567	9.561808	0.311495	-0.506678	0.053692
+1.571511	0.337560	-0.545842	9.478016	0.319622	-0.511342	0.056224
+1.572434	0.409381	-0.586541	9.624053	0.326417	-0.511741	0.058089
+1.573515	0.258557	-0.612875	9.652781	0.334011	-0.511342	0.056757
+1.574512	0.241798	-0.703849	9.705450	0.345069	-0.511741	0.053959
+1.575511	0.229828	-0.794822	9.612083	0.356793	-0.512141	0.051161
+1.576512	0.174765	-0.825945	9.643205	0.368784	-0.512674	0.045299
+1.577511	0.141249	-0.813975	9.564202	0.379842	-0.512541	0.039436
+1.578510	0.112520	-0.744547	9.607294	0.393165	-0.514006	0.032908
+1.579426	0.150825	-0.720607	9.573778	0.406089	-0.517870	0.025047
+1.580428	0.126884	-0.770882	9.640811	0.418213	-0.520934	0.017986
+1.581378	0.138854	-0.778064	9.621659	0.431136	-0.525730	0.013190
+1.582388	0.105338	-0.861855	9.602506	0.442594	-0.532259	0.008793
+1.583392	0.162795	-0.830733	9.513927	0.451521	-0.537188	0.005462
+1.584392	0.220252	-0.768488	9.509139	0.458848	-0.537988	-0.000133
+1.585395	0.342348	-0.679908	9.523503	0.468308	-0.536256	-0.003464
+1.586388	0.366289	-0.718213	9.554625	0.475769	-0.533858	-0.005196
+1.587376	0.339954	-0.706243	9.652781	0.483230	-0.531593	-0.008926
+1.588413	0.339954	-0.715819	9.638417	0.491224	-0.531459	-0.011858
+1.589407	0.397411	-0.706243	9.573778	0.500949	-0.533991	-0.013057
+1.590398	0.497961	-0.770882	9.722208	0.508544	-0.536789	-0.014922
+1.591406	0.533872	-0.718213	9.729391	0.514672	-0.536256	-0.015988
+1.592407	0.541054	-0.715819	9.724603	0.520668	-0.535590	-0.018786
+1.593407	0.612875	-0.744547	9.813182	0.528262	-0.535590	-0.021717
+1.594407	0.672726	-0.778064	9.894580	0.533991	-0.536522	-0.023982
+1.595402	0.706243	-0.816369	9.947249	0.541052	-0.534923	-0.029044
+1.596395	0.739759	-0.811581	9.959219	0.549046	-0.531593	-0.034640
+1.597427	0.706243	-0.883402	10.019070	0.555308	-0.532259	-0.038504
+1.598428	0.660756	-0.933677	10.117226	0.561836	-0.535057	-0.042767
+1.599428	0.600905	-0.976770	10.141166	0.567565	-0.540652	-0.048230
+1.600427	0.588935	-1.082107	10.088497	0.572894	-0.544383	-0.052893
+1.601370	0.509931	-1.106048	10.086103	0.577957	-0.545449	-0.057156
+1.602446	0.553024	-1.134776	10.100467	0.579822	-0.547181	-0.065283
+1.603447	0.562600	-1.094078	10.229746	0.580755	-0.545848	-0.074609
+1.604448	0.562600	-1.079713	10.256080	0.580089	-0.539720	-0.083669
+1.605450	0.495567	-1.055773	10.289597	0.578890	-0.531726	-0.094594
+1.606419	0.409381	-1.132382	10.291991	0.576358	-0.522666	-0.104187
+1.607475	0.368683	-1.046197	10.421269	0.573294	-0.514806	-0.114845
+1.608450	0.277709	-1.036621	10.435633	0.568364	-0.507211	-0.126303
+1.609450	0.225040	-0.974375	10.325507	0.560237	-0.498285	-0.139093
+1.610449	0.141249	-0.921707	10.296779	0.551577	-0.489492	-0.148686
+1.611445	0.055063	-0.892978	10.191441	0.540919	-0.480698	-0.159744
+1.612404	0.090974	-0.840309	10.117226	0.529328	-0.468574	-0.170403
+1.613440	0.074215	-0.802004	10.074133	0.515205	-0.455518	-0.180662
+1.614439	0.062245	-0.744547	9.949643	0.496686	-0.441928	-0.187456
+1.615439	0.050275	-0.694272	9.820364	0.476968	-0.428738	-0.190121
+1.616437	-0.004788	-0.646392	9.772483	0.456051	-0.415948	-0.191187
+1.617438	-0.047881	-0.646392	9.597718	0.434334	-0.402625	-0.191054
+1.618436	-0.004788	-0.696667	9.547443	0.412084	-0.395031	-0.190254
+1.619438	-0.114914	-0.725395	9.456470	0.388502	-0.390767	-0.189588
+1.620509	-0.110126	-0.651180	9.446894	0.365320	-0.386904	-0.187456
+1.621441	-0.057457	-0.574570	9.430135	0.341738	-0.381574	-0.184658
+1.622443	-0.026334	-0.569782	9.468440	0.321087	-0.376511	-0.181861
+1.623445	0.014364	-0.512325	9.554625	0.301369	-0.372381	-0.178263
+1.624509	0.028729	-0.524295	9.473228	0.283250	-0.372115	-0.173734
+1.625512	-0.007182	-0.529083	9.470834	0.266063	-0.371049	-0.170003
+1.626462	0.026334	-0.474021	9.609688	0.249009	-0.370649	-0.165606
+1.627468	0.045487	-0.435716	9.683904	0.233288	-0.373580	-0.164807
+1.628446	0.031123	-0.402199	9.753331	0.219565	-0.376511	-0.164274
+1.629454	0.131672	-0.327984	9.786848	0.206908	-0.369051	-0.161210
+1.630400	0.227434	-0.327984	9.829940	0.193452	-0.351198	-0.155614
+1.631440	0.167583	-0.323196	9.971189	0.182926	-0.335210	-0.150418
+1.632437	0.225040	-0.313620	10.016676	0.175732	-0.329214	-0.146421
+1.633441	0.210676	-0.265739	9.983159	0.171069	-0.334277	-0.140825
+1.634439	0.251375	-0.260951	10.038222	0.164141	-0.344802	-0.136695
+1.635439	0.260951	-0.222646	10.076527	0.155881	-0.353063	-0.133098
+1.636439	0.325590	-0.153219	10.148348	0.148686	-0.357060	-0.129101
+1.637383	0.373471	-0.167583	10.193835	0.143490	-0.356260	-0.124038
+1.638400	0.397411	-0.189129	10.287203	0.139626	-0.351064	-0.116977
+1.639397	0.284891	-0.196312	10.370994	0.135096	-0.349332	-0.111381
+1.640450	0.301649	-0.100550	10.375782	0.128835	-0.352397	-0.105652
+1.641452	0.433322	-0.047881	10.280021	0.121907	-0.358525	-0.098058
+1.642450	0.543448	0.059851	10.303961	0.112714	-0.367185	-0.089398
+1.643449	0.531478	0.088580	10.299173	0.102188	-0.377044	-0.080072
+1.644445	0.548236	0.131672	10.280021	0.093262	-0.385971	-0.065949
+1.645450	0.629633	0.153219	10.347054	0.082737	-0.394498	-0.055158
+1.646392	0.773276	0.208282	10.447604	0.072611	-0.401825	-0.047830
+1.647349	0.983952	0.275315	10.483514	0.064084	-0.406888	-0.042234
+1.648371	1.043803	0.282497	10.600822	0.059288	-0.409553	-0.039836
+1.649443	1.039015	0.263345	10.624763	0.057689	-0.413283	-0.038770
+1.650399	1.141958	0.299255	10.715736	0.059421	-0.418213	-0.040769
+1.651450	1.220962	0.323196	10.873743	0.062752	-0.427406	-0.041168
+1.652444	1.256873	0.452474	10.897684	0.067015	-0.438331	-0.042900
+1.653452	1.366999	0.555418	11.031750	0.073011	-0.449655	-0.047697
+1.654450	1.489095	0.550630	11.232850	0.081404	-0.459515	-0.049962
+1.655448	1.632737	0.610481	11.326217	0.091263	-0.468041	-0.052093
+1.656449	1.766804	0.699061	11.419585	0.101389	-0.473371	-0.055557
+1.657451	1.881718	0.790034	11.551257	0.112047	-0.480299	-0.058355
+1.658448	1.936781	0.861855	11.699688	0.122573	-0.487493	-0.057289
+1.659429	1.960721	0.847491	11.685324	0.134430	-0.494554	-0.056890
+1.660466	1.967903	0.912130	11.699688	0.147487	-0.504813	-0.052760
+1.661452	2.013390	0.974375	11.749963	0.158812	-0.516271	-0.049162
+1.662449	1.977479	0.988740	11.690112	0.166806	-0.526930	-0.047963
+1.663392	1.922417	1.024650	11.625473	0.174266	-0.534257	-0.048230
+1.664371	1.908052	1.012680	11.551257	0.182793	-0.541319	-0.047564
+1.665441	1.829049	0.983952	11.448313	0.191587	-0.547047	-0.044899
+1.666434	1.754833	0.948041	11.275942	0.198781	-0.551311	-0.041035
+1.667435	1.685406	0.914524	11.187363	0.206508	-0.557306	-0.040502
+1.668505	1.630343	0.943253	11.146664	0.213703	-0.562369	-0.037704
+1.669477	1.536976	0.979164	11.096389	0.221963	-0.566100	-0.035306
+1.670465	1.496277	0.979164	11.010204	0.229691	-0.569963	-0.033441
+1.671507	1.407697	0.962405	10.945564	0.235953	-0.573427	-0.033574
+1.672511	1.345452	0.976770	10.890501	0.240083	-0.574893	-0.033041
+1.673514	1.350240	0.916918	10.754041	0.245412	-0.572095	-0.032375
+1.674509	1.295177	0.878614	10.679826	0.253273	-0.567832	-0.034507
+1.675510	1.242508	0.861855	10.667855	0.260467	-0.566233	-0.037438
+1.676509	1.177869	0.835521	10.562518	0.267795	-0.567432	-0.037305
+1.677510	1.149141	0.746941	10.495484	0.278720	-0.565966	-0.036772
+1.678466	1.129988	0.713425	10.387752	0.289645	-0.568364	-0.039703
+1.679460	1.101260	0.617663	10.359024	0.301636	-0.571695	-0.045565
+1.680423	1.048591	0.560206	10.332689	0.314292	-0.568631	-0.050228
+1.681434	1.024650	0.533872	10.342266	0.328282	-0.563435	-0.056623
+1.682438	1.046197	0.524295	10.198623	0.342538	-0.562636	-0.065683
+1.683438	0.991134	0.490779	10.093285	0.357726	-0.565300	-0.073810
+1.684435	0.983952	0.466838	9.997523	0.371315	-0.566499	-0.079672
+1.685374	1.036621	0.462050	10.043010	0.384639	-0.568498	-0.083936
+1.686446	1.048591	0.454868	10.040616	0.398761	-0.569297	-0.091130
+1.687445	1.031833	0.466838	9.975977	0.413816	-0.570096	-0.098991
+1.688450	1.201810	0.505143	9.925702	0.427806	-0.568897	-0.106452
+1.689417	1.328694	0.442898	9.870639	0.440596	-0.565300	-0.112847
+1.690444	1.264055	0.373471	9.889792	0.449655	-0.561303	-0.115378
+1.691447	1.208992	-0.268133	9.827546	0.466709	-0.582620	-0.095260
+1.692449	1.900870	-0.885796	9.475622	0.501882	-0.624721	-0.053692
+1.693451	2.389255	-0.409381	9.391831	0.530527	-0.642308	-0.023715
+1.694450	2.113940	0.356712	9.391831	0.537588	-0.632049	-0.024248
+1.695449	1.903264	0.720607	9.200307	0.530260	-0.614995	-0.039170
+1.696448	1.790744	0.845097	9.274522	0.524398	-0.605536	-0.047830
+1.697445	1.491489	0.837915	9.324797	0.527729	-0.607801	-0.048629
+1.698437	1.374181	0.785246	9.327191	0.533858	-0.606069	-0.051427
+1.699436	1.386151	0.833127	9.315221	0.536256	-0.598608	-0.061286
+1.700436	1.436426	0.950435	9.202701	0.535989	-0.587417	-0.075942
+1.701422	1.477125	1.125200	9.166791	0.531992	-0.574360	-0.091530
+1.702408	1.474730	1.197021	9.118910	0.526263	-0.564234	-0.105652
+1.703414	1.374181	1.163505	9.109333	0.522133	-0.556773	-0.111115
+1.704438	1.352634	1.185051	9.142850	0.519469	-0.549312	-0.113646
+1.705440	1.422062	1.110836	9.027936	0.519868	-0.545315	-0.114979
+1.706438	1.436426	0.943253	8.982449	0.522000	-0.545582	-0.115911
+1.707434	1.465154	0.797216	9.054271	0.524531	-0.549046	-0.114179
+1.708438	1.563310	0.646392	8.948933	0.530260	-0.555574	-0.108717
+1.709427	1.730893	0.553024	8.881899	0.537855	-0.561836	-0.104054
+1.710440	1.716529	0.469232	8.898658	0.543583	-0.567698	-0.098191
+1.711464	1.759622	0.409381	8.817260	0.549179	-0.569031	-0.088732
+1.712468	1.747651	0.351924	8.786138	0.555974	-0.571562	-0.080472
+1.713394	1.781168	0.330378	8.786138	0.563035	-0.576358	-0.071945
+1.714390	1.838625	0.265739	8.661647	0.567032	-0.583686	-0.062219
+1.715391	1.857777	0.272921	8.659253	0.566632	-0.593279	-0.050628
+1.716396	1.979874	0.332772	8.714316	0.561037	-0.599008	-0.040369
+1.717375	2.013390	0.490779	8.659253	0.552510	-0.602072	-0.027179
+1.718370	2.025360	0.675120	8.728681	0.540519	-0.606735	-0.011724
+1.719371	2.080423	0.873826	8.721499	0.524798	-0.615528	0.001998
+1.720370	2.161821	0.969587	8.668830	0.504813	-0.627519	0.016654
+1.721370	2.219278	1.173081	8.697558	0.479100	-0.635913	0.032775
+1.722369	2.192943	1.340664	8.642495	0.449256	-0.644306	0.050361
+1.723368	2.152245	1.438820	8.735863	0.415681	-0.653632	0.068614
+1.724368	2.070847	1.548946	8.750227	0.379309	-0.661760	0.087400
+1.725369	2.171397	1.529793	8.640101	0.343737	-0.672018	0.108983
+1.726368	2.216884	1.513035	8.592220	0.306965	-0.682277	0.129767
+1.727368	2.300675	1.532187	8.793320	0.269260	-0.691870	0.152417
+1.728368	2.367708	1.477125	8.802896	0.231023	-0.699198	0.175466
+1.729368	2.482623	1.419667	8.836413	0.194251	-0.704926	0.197449
+1.730390	2.549656	1.453184	8.960903	0.157879	-0.709190	0.215035
+1.731390	2.564020	1.347846	8.970479	0.123772	-0.713587	0.230090
+1.732389	2.614295	1.220962	8.999208	0.092329	-0.721714	0.248476
+1.733422	2.654994	1.134776	8.920204	0.063018	-0.732106	0.270459
+1.734463	2.757937	0.919312	8.929780	0.035440	-0.738368	0.291910
+1.735499	2.757937	0.768488	9.039906	0.007727	-0.745029	0.318289
+1.736508	2.690904	0.641604	9.037512	-0.020651	-0.755688	0.335476
+1.737513	2.633447	0.529083	9.035118	-0.053825	-0.767145	0.337475
+1.738508	2.568808	0.529083	9.044694	-0.084069	-0.777404	0.343603
+1.739511	2.669358	0.660756	9.047088	-0.116444	-0.785531	0.361856
+1.740510	2.796242	0.737365	8.862747	-0.146821	-0.793126	0.388502
+1.741511	2.860881	0.873826	8.783744	-0.178130	-0.799654	0.410885
+1.742467	2.937491	1.046197	8.755015	-0.207974	-0.802319	0.424075
+1.743466	2.765120	1.156323	8.807684	-0.237152	-0.801519	0.427273
+1.744508	2.595143	1.223356	8.731075	-0.266995	-0.797922	0.424741
+1.745513	2.391649	1.249690	8.601796	-0.297905	-0.797922	0.420478
+1.746461	2.192943	1.192233	8.630525	-0.326283	-0.799121	0.412217
+1.747439	2.010996	1.098866	8.551521	-0.350931	-0.796323	0.398628
+1.748439	1.764410	0.998316	8.458154	-0.369850	-0.787263	0.379043
+1.749438	1.446002	0.983952	8.321693	-0.384772	-0.773674	0.355727
+1.750434	1.082107	0.897766	8.321693	-0.394897	-0.757953	0.332012
+1.751433	0.957617	0.811581	8.213961	-0.399827	-0.747427	0.309496
+1.752435	0.883402	0.828339	8.070319	-0.400227	-0.736369	0.286847
+1.753437	0.878614	0.821157	7.936252	-0.397162	-0.719848	0.263931
+1.754509	0.727789	0.907342	7.962587	-0.392766	-0.700263	0.244879
+1.755510	0.598511	0.936071	7.943435	-0.389302	-0.684542	0.229557
+1.756510	0.600905	1.010286	7.780640	-0.384505	-0.671752	0.212104
+1.757513	0.581752	1.012680	7.632209	-0.376645	-0.661893	0.195717
+1.758509	0.699061	0.981558	7.579540	-0.368384	-0.650435	0.180662
+1.759510	0.720607	1.070137	7.421533	-0.360257	-0.643640	0.165873
+1.760509	0.926495	1.089290	7.294649	-0.347201	-0.630850	0.155747
+1.761461	0.888190	1.110836	7.141430	-0.330280	-0.610466	0.148153
+1.762459	0.730183	1.163505	7.086367	-0.313760	-0.589681	0.136695
+1.763460	0.713425	1.168293	7.064821	-0.298704	-0.582487	0.119908
+1.764436	0.802004	1.280813	6.885268	-0.282051	-0.585818	0.099391
+1.765407	0.979164	1.417273	6.617135	-0.267262	-0.586884	0.071678
+1.766404	1.113230	1.254479	6.473492	-0.251008	-0.579822	0.037438
+1.767405	1.371787	0.833127	6.583618	-0.227159	-0.567165	0.011325
+1.768405	1.316724	0.272921	6.787112	-0.184126	-0.556907	0.003864
+1.769450	0.873826	-0.011970	6.811052	-0.132032	-0.544250	-0.003597
+1.770450	0.418958	0.294467	6.538131	-0.093528	-0.524398	-0.026113
+1.771450	0.090974	0.857067	6.188601	-0.075675	-0.494155	-0.046364
+1.772430	0.028729	1.292783	6.035382	-0.068614	-0.457783	-0.059688
+1.773432	-0.100550	1.639919	6.047353	-0.070213	-0.422743	-0.066882
+1.774445	-0.031123	2.034937	6.145508	-0.074210	-0.396496	-0.071012
+1.775445	0.208282	2.377285	6.195783	-0.081404	-0.376911	-0.068881
+1.776449	0.454868	2.733997	6.370548	-0.091930	-0.362256	-0.065283
+1.777452	0.723001	2.877640	6.480674	-0.105519	-0.351864	-0.065816
+1.778450	1.079713	3.026070	6.597982	-0.118576	-0.344003	-0.062752
+1.779387	1.426850	3.152955	6.679380	-0.130833	-0.336009	-0.056757
+1.780376	1.651890	3.169713	6.739231	-0.142557	-0.327882	-0.050228
+1.781434	1.807502	3.140984	6.830205	-0.152283	-0.320021	-0.048496
+1.782436	1.929599	3.018888	6.700926	-0.158412	-0.313893	-0.051028
+1.783436	2.025360	2.805818	6.763171	-0.158012	-0.312694	-0.059821
+1.784426	2.049301	2.508957	6.763171	-0.149219	-0.322286	-0.075675
+1.785513	2.123516	2.212096	6.973847	-0.139493	-0.344802	-0.092995
+1.786467	2.425166	2.101970	7.220434	-0.134963	-0.376378	-0.105652
+1.787510	2.719633	2.152245	7.423927	-0.135363	-0.402758	-0.111781
+1.788509	2.906368	2.152245	7.246768	-0.136562	-0.414749	-0.113247
+1.789513	3.140984	2.173791	7.222828	-0.136429	-0.417413	-0.111381
+1.790510	3.349266	2.097182	7.287467	-0.138294	-0.414349	-0.107118
+1.791476	3.452210	2.013390	7.304225	-0.139493	-0.403691	-0.098325
+1.792435	3.445028	1.943963	7.347318	-0.140426	-0.381308	-0.081937
+1.793494	3.363630	1.852989	7.325771	-0.142158	-0.355328	-0.067681
+1.794510	3.167319	1.829049	7.419139	-0.147221	-0.334544	-0.055291
+1.795509	3.016494	1.706953	7.522083	-0.150285	-0.305100	-0.043433
+1.796446	2.978189	1.501065	7.598692	-0.151617	-0.273391	-0.031043
+1.797448	2.690904	1.551340	7.672908	-0.155081	-0.251008	-0.022783
+1.798436	2.626265	1.460366	7.682484	-0.158945	-0.231156	-0.020784
+1.799436	2.623871	1.395727	7.610663	-0.160810	-0.216634	-0.017187
+1.800437	2.590354	1.378969	7.565176	-0.160677	-0.209306	-0.012923
+1.801437	2.516139	1.355028	7.555600	-0.161210	-0.204643	-0.012524
+1.802435	2.470652	1.357422	7.514901	-0.158812	-0.202245	-0.010126
+1.803411	2.458682	1.352634	7.493354	-0.153616	-0.199847	-0.004263
+1.804439	2.504169	1.419667	7.459838	-0.147087	-0.196116	-0.000933
+1.805374	2.597537	1.477125	7.450262	-0.140959	-0.189322	-0.001466
+1.806454	2.575990	1.474730	7.502931	-0.135096	-0.185591	-0.001466
+1.807450	2.640629	1.426850	7.447868	-0.128568	-0.185058	0.002132
+1.808444	2.813000	1.532187	7.498143	-0.121907	-0.185191	0.006129
+1.809387	2.865669	1.548946	7.467020	-0.114446	-0.183060	0.010925
+1.810449	2.997342	1.565704	7.562782	-0.107384	-0.177730	0.016254
+1.811449	3.126620	1.558522	7.711212	-0.103121	-0.174400	0.018386
+1.812406	3.222382	1.539370	7.830915	-0.097126	-0.169070	0.018652
+1.813378	3.349266	1.546552	7.996104	-0.088066	-0.165207	0.019985
+1.814335	3.358842	1.539370	8.012862	-0.075409	-0.168538	0.023449
+1.815372	3.447422	1.546552	8.077501	-0.063418	-0.174933	0.028645
+1.816446	3.533607	1.575280	8.063137	-0.052760	-0.181594	0.033841
+1.817425	3.612611	1.544158	8.161292	-0.041435	-0.188522	0.037571
+1.818457	3.729919	1.474730	8.316905	-0.026113	-0.197449	0.040769
+1.819462	3.765830	1.328694	8.398303	-0.008127	-0.207574	0.044233
+1.820461	3.751465	1.268843	8.477306	0.011724	-0.216634	0.046364
+1.821462	3.701190	1.177869	8.501247	0.031975	-0.224228	0.049828
+1.822462	3.746677	1.060561	8.561098	0.054092	-0.229025	0.050894
+1.823457	3.722737	0.991134	8.506035	0.076208	-0.233155	0.053159
+1.824421	3.670068	0.881008	8.518005	0.098858	-0.237685	0.053825
+1.825430	3.638945	0.778064	8.575462	0.121374	-0.242881	0.056224
+1.826466	3.581488	0.754124	8.556310	0.145355	-0.247144	0.058622
+1.827462	3.495303	0.675120	8.415061	0.166539	-0.249409	0.059821
+1.828462	3.461786	0.564994	8.465336	0.186790	-0.252873	0.058222
+1.829463	3.425875	0.483597	8.383938	0.204643	-0.256070	0.057156
+1.830385	3.366024	0.397411	8.328875	0.221430	-0.257802	0.057822
+1.831385	3.358842	0.296861	8.316905	0.235819	-0.259002	0.060221
+1.832385	3.337296	0.201100	8.206779	0.248743	-0.259668	0.059021
+1.833386	3.320538	0.064639	8.144534	0.261400	-0.261933	0.058489
+1.834460	3.215200	0.016758	8.161292	0.272058	-0.263665	0.057289
+1.835406	3.133802	-0.057457	8.125382	0.279786	-0.264597	0.056490
+1.836464	3.162531	-0.205888	8.178051	0.284715	-0.265130	0.056890
+1.837464	3.117044	-0.237010	8.235508	0.290577	-0.266729	0.058222
+1.838387	3.093104	-0.296861	8.146928	0.295640	-0.267795	0.059821
+1.839350	3.066769	-0.375865	8.259448	0.299237	-0.267662	0.060620
+1.840373	2.966219	-0.395017	8.357604	0.303101	-0.266862	0.060887
+1.841457	2.901580	-0.383047	8.292965	0.304833	-0.268727	0.065949
+1.842464	2.868063	-0.438110	8.280995	0.303767	-0.271126	0.073677
+1.843461	2.803424	-0.495567	8.273813	0.302568	-0.271259	0.079806
+1.844467	2.841729	-0.502749	8.197203	0.301369	-0.270193	0.087533
+1.845407	2.810606	-0.505143	8.190021	0.300570	-0.271658	0.094861
+1.846409	2.781878	-0.464444	8.146928	0.298838	-0.274590	0.102988
+1.847385	2.745967	-0.385441	8.077501	0.296573	-0.275123	0.114845
+1.848385	2.712451	-0.342348	8.063137	0.295773	-0.276455	0.128701
+1.849386	2.698086	-0.268133	8.034408	0.291643	-0.281518	0.142824
+1.850385	2.614295	-0.174765	8.012862	0.286447	-0.289112	0.158412
+1.851385	2.520927	-0.088580	7.991315	0.280851	-0.297505	0.174533
+1.852386	2.449106	-0.035911	7.919494	0.278587	-0.307098	0.186657
+1.853385	2.298281	0.088580	7.979345	0.278320	-0.318556	0.195317
+1.854386	2.305463	0.055063	7.771063	0.284582	-0.326816	0.189188
+1.855385	1.898476	-0.215464	7.404775	0.321753	-0.357992	0.149485
+1.856386	0.840309	-1.101260	7.127066	0.387703	-0.461113	0.072478
+1.857381	1.448396	-1.199416	8.424637	0.406355	-0.618992	0.014922
+1.858385	2.573596	0.459656	9.327191	0.384372	-0.757686	0.006262
+1.859385	3.224776	1.584856	8.745439	0.350132	-0.815508	0.019985
+1.860385	3.658098	1.975085	8.156504	0.319222	-0.818839	0.039037
+1.861385	3.806528	2.001420	8.161292	0.301902	-0.803251	0.062086
+1.862385	3.813710	1.915234	8.204385	0.296706	-0.789395	0.081671
+1.863385	3.801740	1.977479	8.506035	0.286447	-0.771009	0.106585
+1.864385	3.686826	1.931993	8.620949	0.269527	-0.734371	0.135496
+1.865373	3.514455	1.805108	8.539551	0.252074	-0.680945	0.162675
+1.866371	3.411511	1.692588	8.587432	0.232089	-0.622723	0.189988
+1.867370	3.375601	1.651890	8.699952	0.206642	-0.573028	0.219565
+1.868371	3.184077	1.592039	8.687982	0.180795	-0.536522	0.245545
+1.869371	2.975795	1.426850	8.625737	0.156547	-0.512008	0.265263
+1.870370	2.901580	1.290389	8.608979	0.122706	-0.540786	0.281251
+1.871371	2.532897	1.230538	8.640101	0.102455	-0.556240	0.301902
+1.872371	2.652600	0.778064	8.671224	0.090064	-0.537588	0.314159
+1.873371	2.671752	0.548236	8.697558	0.086067	-0.506412	0.322286
+1.874377	2.736391	0.392623	8.673618	0.087533	-0.479233	0.328415
+1.875371	2.865669	0.246586	8.484488	0.086734	-0.476568	0.327616
+1.876371	2.927915	0.095762	8.376756	0.087266	-0.484029	0.325084
+1.877370	3.131408	0.040699	8.338452	0.093395	-0.482963	0.322020
+1.878371	3.267869	0.002394	8.381544	0.107917	-0.471106	0.321887
+1.879370	3.363630	-0.059851	8.594614	0.129368	-0.445792	0.323885
+1.880357	3.507273	0.031123	8.719104	0.150685	-0.416614	0.324285
+1.881371	3.670068	0.148431	8.992025	0.171735	-0.385305	0.323885
+1.882371	3.890320	0.275315	9.250582	0.190121	-0.352263	0.326283
+1.883370	4.182393	0.598511	9.422953	0.204510	-0.327083	0.327216
+1.884371	4.507983	0.892978	9.659963	0.215302	-0.310828	0.327616
+1.885371	4.725841	1.015074	9.904156	0.223828	-0.310029	0.329348
+1.886371	4.900606	1.278419	10.081315	0.230090	-0.324018	0.332812
+1.887371	5.180709	1.417273	10.258474	0.235286	-0.344936	0.335077
+1.888366	5.448842	1.496277	10.421269	0.239683	-0.367452	0.336409
+1.889377	5.654729	1.611191	10.576882	0.245012	-0.389302	0.332145
+1.890371	5.793584	1.618373	10.775587	0.254338	-0.414482	0.321887
+1.891367	5.910892	1.541764	10.876137	0.264198	-0.440729	0.306565
+1.892372	5.985107	1.505853	10.983869	0.275789	-0.468041	0.288179
+1.893371	6.049747	1.436426	10.976687	0.287513	-0.496953	0.263132
+1.894371	6.088051	1.295177	11.060479	0.300570	-0.525997	0.238084
+1.895371	6.047353	1.134776	11.137088	0.317623	-0.551844	0.208507
+1.896356	6.006654	0.900160	11.321429	0.342138	-0.575559	0.176665
+1.897371	5.934833	0.768488	11.311853	0.368384	-0.595810	0.143224
+1.898365	5.812736	0.643998	11.376492	0.394764	-0.615129	0.111248
+1.899371	5.776826	0.548236	11.421979	0.422343	-0.637378	0.084202
+1.900370	5.757673	0.529083	11.453102	0.449256	-0.665757	0.059688
+1.901371	5.755279	0.591329	11.369310	0.476568	-0.695201	0.041035
+1.902370	5.858223	0.660756	11.345370	0.498818	-0.724911	0.027712
+1.903386	5.910892	0.809187	11.393250	0.516538	-0.754489	0.019452
+1.904370	5.989896	0.885796	11.443525	0.532126	-0.781934	0.011191
+1.905371	6.004260	1.055773	11.426767	0.545449	-0.805916	0.005862
+1.906371	6.064111	1.115624	11.402827	0.553176	-0.827899	0.003997
+1.907370	6.128750	1.137170	11.302277	0.559704	-0.849616	0.004663
+1.908371	6.195783	1.244902	11.383674	0.566766	-0.869201	0.003198
+1.909372	6.171843	1.287995	11.414797	0.573028	-0.890784	0.002798
+1.910370	6.032988	1.323906	11.366916	0.578490	-0.917031	0.002265
+1.911362	5.882164	1.278419	11.321429	0.582887	-0.946741	0.001599
+1.912370	5.874981	1.230538	11.230456	0.589282	-0.970590	-0.000133
+1.913371	6.028200	1.122806	11.103571	0.595943	-0.987510	-0.012257
+1.914371	6.071293	1.084501	11.046114	0.604870	-0.989508	-0.027179
+1.915371	6.030594	1.062955	11.024568	0.617260	-0.982980	-0.040636
+1.916372	5.894134	0.950435	10.859379	0.631116	-0.981248	-0.054625
+1.917371	5.575726	0.823551	10.663067	0.646172	-1.001899	-0.065550
+1.918399	5.377021	0.617663	10.428451	0.664557	-1.033075	-0.077407
+1.919371	5.156769	0.392623	10.098073	0.684009	-1.065850	-0.091130
+1.920374	4.687536	0.052669	9.806000	0.706659	-1.106352	-0.112314
+1.921371	4.084237	-0.495567	9.715026	0.739300	-1.166706	-0.142424
+1.922371	3.885532	-0.916918	9.755725	0.769943	-1.266096	-0.179862
+1.923371	4.201545	-0.548236	9.918520	0.790727	-1.377611	-0.201845
+1.924370	4.395463	0.112520	9.549837	0.808047	-1.463545	-0.201979
+1.925372	4.536711	0.387835	9.082999	0.821637	-1.514706	-0.187856
+1.926372	4.579804	0.493173	9.116516	0.829364	-1.546815	-0.163342
+1.927368	4.347582	0.505143	9.212277	0.839890	-1.575726	-0.133498
+1.928374	4.208728	0.651180	9.150032	0.861473	-1.593579	-0.106052
+1.929449	4.081843	0.825945	9.109333	0.881191	-1.592646	-0.073011
+1.930374	4.007628	1.034227	9.224248	0.888652	-1.579057	-0.031576
+1.931366	3.928625	1.204204	9.061453	0.898911	-1.556407	0.012923
+1.932371	3.866379	1.323906	8.953721	0.913300	-1.529095	0.055691
+1.933374	3.892714	1.316724	9.152426	0.913567	-1.508444	0.101256
+1.934399	4.000446	1.424456	9.272128	0.906639	-1.497119	0.149219
+1.935399	4.120148	1.508247	8.984843	0.907305	-1.490191	0.191320
+1.936372	4.117754	1.625555	8.987237	0.907172	-1.491391	0.226360
+1.937409	4.108178	1.642313	9.166791	0.898245	-1.504314	0.261133
+1.938407	4.227880	1.565704	9.197913	0.887986	-1.520035	0.293908
+1.939360	4.340400	1.479519	9.236218	0.879726	-1.532426	0.321753
+1.940408	4.467284	1.374181	9.482804	0.872398	-1.542818	0.343870
+1.941387	4.620503	1.347846	9.652781	0.867202	-1.553343	0.361590
+1.942409	4.802450	1.290389	9.786848	0.863072	-1.562136	0.377311
+1.943410	4.974821	1.194627	9.944854	0.860008	-1.563735	0.389302
+1.944409	5.180709	1.158717	10.117226	0.858542	-1.561603	0.394098
+1.945410	5.269289	1.106048	10.306355	0.858942	-1.564668	0.394364
+1.946387	5.396173	1.139564	10.440421	0.862273	-1.576259	0.394498
+1.947387	5.520663	1.039015	10.627157	0.868801	-1.593312	0.393965
+1.948385	5.642759	0.938465	10.816286	0.869734	-1.619426	0.392766
+1.949386	5.817524	0.845097	10.861773	0.868002	-1.653400	0.388502
+1.950391	5.927650	0.818763	10.871349	0.870666	-1.688706	0.380642
+1.951412	6.037776	0.794822	11.046114	0.875462	-1.722813	0.372781
+1.952408	6.133538	0.766094	11.062873	0.878260	-1.755055	0.363455
+1.953409	6.310697	0.794822	11.055690	0.872798	-1.784100	0.357193
+1.954402	6.372942	0.720607	10.947958	0.860940	-1.813810	0.353995
+1.955404	6.281969	0.655968	10.931200	0.847351	-1.848051	0.352130
+1.956406	6.243664	0.524295	11.022174	0.830164	-1.886954	0.355994
+1.957410	6.212542	0.469232	11.012598	0.806182	-1.929855	0.359858
+1.958408	6.246058	0.483597	11.012598	0.774207	-1.966626	0.365453
+1.959409	6.267604	0.514719	11.038932	0.752490	-1.990874	0.372648
+1.960407	6.246058	0.483597	10.866561	0.734237	-2.010726	0.379709
+1.961405	6.341820	0.457262	10.947958	0.704660	-2.027380	0.384106
+1.962462	6.337032	0.442898	10.947958	0.664557	-2.044833	0.389435
+1.963405	6.313091	0.409381	11.134694	0.623389	-2.059489	0.397562
+1.964380	6.337032	0.373471	11.120330	0.595410	-2.073611	0.410485
+1.965386	6.255634	0.311226	10.955141	0.573294	-2.092930	0.420611
+1.966386	6.248452	0.287285	10.931200	0.543850	-2.122640	0.432335
+1.967461	6.234088	0.311226	10.830650	0.510276	-2.155415	0.443394
+1.968463	6.167055	0.359106	10.775587	0.477234	-2.184593	0.452054
+1.969446	6.145508	0.485991	10.619975	0.442061	-2.211239	0.456583
+1.970462	6.095233	0.684696	10.481120	0.412750	-2.238818	0.456717
+1.971464	6.021018	0.845097	10.196229	0.398228	-2.270394	0.451254
+1.972462	6.128750	1.127594	10.294385	0.379576	-2.298639	0.443394
+1.973464	6.061717	1.216174	10.447604	0.352663	-2.318623	0.438064
+1.974469	5.882164	1.292783	10.263262	0.320688	-2.332879	0.430070
+1.975415	5.726551	1.412485	9.762907	0.292576	-2.350332	0.410086
+1.976461	5.637971	1.450790	9.557020	0.271658	-2.370583	0.378643
+1.977464	5.487146	1.477125	9.478016	0.255005	-2.380842	0.346401
+1.978462	5.398567	1.592039	9.329585	0.247810	-2.366187	0.313893
+1.979407	5.381809	1.690194	9.085393	0.244479	-2.331813	0.276188
+1.980385	5.286047	1.778774	9.181155	0.235953	-2.284383	0.237418
+1.981385	5.216620	1.819473	9.403801	0.225960	-2.227093	0.200513
+1.982385	5.051431	1.800320	9.269734	0.217567	-2.165407	0.166806
+1.983465	4.788086	1.649496	9.372678	0.215968	-2.107052	0.140026
+1.984462	4.524741	1.623161	9.348738	0.229824	-2.051228	0.117377
+1.985425	4.524741	1.623161	9.348738	0.243547	-2.003798	0.097925
+1.986455	4.457708	1.637525	9.015966	0.251141	-1.952504	0.075276
+1.987463	4.256608	1.596827	8.999208	0.252473	-1.902409	0.061420
+1.988458	4.239850	1.527399	8.936962	0.253939	-1.841522	0.054225
+1.989465	4.218304	1.522611	8.944145	0.263265	-1.767979	0.049162
+1.990463	4.345188	1.692588	8.999208	0.280185	-1.686175	0.037038
+1.991419	4.469678	1.886506	8.934568	0.294175	-1.612098	0.025447
+1.992463	4.457708	2.152245	8.683194	0.299904	-1.546415	0.022116
+1.993462	4.512771	2.269553	8.518005	0.299637	-1.493389	0.022383
+1.994418	4.577410	2.410801	8.297753	0.302168	-1.448490	0.025181
+1.995429	4.852725	2.461076	8.089471	0.308830	-1.401726	0.028778
+1.996406	4.891030	2.597537	7.991315	0.317757	-1.359891	0.039170
+1.997385	4.692324	2.595143	8.020044	0.330813	-1.323386	0.061420
+1.998384	4.464890	2.619083	8.048772	0.340406	-1.296873	0.089398
+1.999385	4.357158	2.611901	7.914706	0.347067	-1.279686	0.118176
+2.000463	4.424191	2.609507	7.716000	0.349332	-1.273291	0.142291
+2.001462	4.706688	2.748361	7.615451	0.344669	-1.275289	0.157746
+2.002460	5.094523	2.913550	7.483778	0.336142	-1.280086	0.167738
+2.003464	5.415325	3.035646	7.495749	0.324418	-1.283283	0.174000
+2.004461	5.721763	3.061981	7.507719	0.312427	-1.283017	0.178263
+2.005433	6.076081	3.117044	7.625027	0.304300	-1.276888	0.181861
+2.006459	6.370548	3.081133	7.636997	0.300969	-1.269294	0.184925
+2.007462	6.514191	2.971007	7.835703	0.300836	-1.265564	0.188789
+2.008463	6.619529	2.676540	7.988921	0.299104	-1.280752	0.193452
+2.009463	6.643469	2.384467	7.960193	0.302168	-1.285681	0.202778
+2.010462	6.609953	2.109152	7.957799	0.306698	-1.285948	0.211971
+2.011464	6.686562	1.738075	7.972163	0.310029	-1.292609	0.219965
+2.012395	6.691350	1.414879	8.070319	0.311628	-1.303668	0.223029
+2.013388	6.574042	1.153929	8.089471	0.308297	-1.313926	0.220498
+2.014384	6.370548	0.926495	8.240296	0.304034	-1.316325	0.216234
+2.015386	6.214936	0.622451	8.336058	0.299904	-1.316325	0.207841
+2.016454	5.958773	0.332772	8.381544	0.293775	-1.311528	0.190521
+2.017464	5.673882	0.153219	8.316905	0.286580	-1.305666	0.171202
+2.018461	5.403355	-0.088580	8.254660	0.279119	-1.295274	0.151617
+2.019461	5.113676	-0.277709	8.211567	0.269660	-1.280885	0.132165
+2.020461	4.970033	-0.402199	8.190021	0.260467	-1.263965	0.113779
+2.021463	4.773722	-0.500355	8.005680	0.251807	-1.244779	0.095926
+2.022462	4.596562	-0.663150	7.912312	0.241415	-1.224528	0.084868
+2.023462	4.467284	-0.672726	7.739941	0.232222	-1.203744	0.078473
+2.024419	4.448132	-0.612875	7.627421	0.219698	-1.183093	0.074476
+2.025439	4.529529	-0.541054	7.567570	0.204243	-1.163242	0.073277
+2.026440	4.570228	-0.445292	7.457444	0.188256	-1.144323	0.077008
+2.027458	4.728235	-0.366289	7.388017	0.169737	-1.129002	0.087266
+2.028462	4.986792	-0.263345	7.464626	0.147620	-1.117943	0.101789
+2.029451	5.221408	-0.270527	7.438292	0.125237	-1.111015	0.117910
+2.030393	5.465600	-0.158007	7.483778	0.102455	-1.109949	0.137495
+2.031380	5.767250	-0.074215	7.498143	0.080338	-1.112614	0.159478
+2.032385	6.080869	-0.093368	7.591510	0.058755	-1.118476	0.180662
+2.033443	6.456734	-0.107732	7.648967	0.037838	-1.127669	0.203444
+2.034461	6.801476	-0.169977	7.771063	0.016787	-1.139793	0.224761
+2.035453	7.143824	-0.265739	7.806974	-0.005462	-1.156580	0.248476
+2.036458	7.443080	-0.301649	7.833309	-0.028378	-1.175366	0.272591
+2.037464	7.687272	-0.325590	7.799792	-0.048363	-1.196683	0.299237
+2.038398	7.859643	-0.304043	7.907524	-0.066083	-1.221730	0.325617
+2.039462	7.998498	-0.289679	7.945829	-0.080472	-1.248377	0.354129
+2.040459	8.094259	-0.287285	7.919494	-0.091663	-1.279420	0.383839
+2.041467	8.201991	-0.237010	7.850067	-0.096593	-1.312994	0.414216
+2.042462	8.259448	-0.179553	7.876401	-0.095660	-1.346302	0.447923
+2.043460	8.211567	0.002394	7.905130	-0.097126	-1.385605	0.477634
+2.044457	8.316905	0.234616	7.814156	-0.098458	-1.416115	0.504813
+2.045423	8.316905	0.481203	7.840491	-0.099391	-1.442361	0.529861
+2.046406	8.249872	0.670332	7.778246	-0.097792	-1.475136	0.555041
+2.047384	8.230720	0.833127	7.488566	-0.094994	-1.497386	0.578224
+2.048377	8.158898	1.058167	7.268314	-0.090198	-1.508311	0.598208
+2.049385	8.075107	1.280813	7.263526	-0.084735	-1.525364	0.614462
+2.050461	7.972163	1.472336	6.995394	-0.082070	-1.545083	0.634181
+2.051462	7.960193	1.601615	6.734443	-0.081138	-1.565467	0.652833
+2.052457	7.885978	1.680618	6.518979	-0.079273	-1.593979	0.670553
+2.053462	7.766275	1.788350	6.384913	-0.075009	-1.623423	0.688006
+2.054462	7.759093	1.788350	6.286757	-0.075942	-1.650735	0.701729
+2.055424	7.747123	1.920022	6.133538	-0.082870	-1.679913	0.715585
+2.056460	7.651361	1.970297	6.059323	-0.082870	-1.704161	0.733172
+2.057465	7.646573	1.898476	6.073687	-0.083936	-1.726544	0.750891
+2.058462	7.646573	1.917628	6.056929	-0.092995	-1.751325	0.762749
+2.059462	7.569964	1.941569	6.109598	-0.106185	-1.770910	0.771009
+2.060461	7.627421	1.915234	6.157479	-0.114845	-1.780636	0.778603
+2.061511	7.804580	1.829049	6.372942	-0.119908	-1.782767	0.789928
+2.062509	7.859643	1.829049	6.459128	-0.130300	-1.786498	0.798855
+2.063462	7.830915	1.771592	6.439976	-0.148953	-1.802885	0.805250
+2.064436	7.811762	1.783562	6.289151	-0.166672	-1.825801	0.816441
+2.065410	7.840491	1.750045	6.298727	-0.176132	-1.849649	0.831230
+2.066438	7.890766	1.599221	6.344214	-0.185058	-1.883090	0.841755
+2.067435	7.763881	1.462760	6.224512	-0.197182	-1.928123	0.846418
+2.068435	7.507719	1.323906	6.025806	-0.206109	-1.974087	0.852680
+2.069373	7.368864	1.223356	5.894134	-0.216767	-2.040570	0.853879
+2.070447	6.961877	0.974375	5.688246	-0.219032	-2.129568	0.847351
+2.071450	6.277181	0.416563	5.736127	-0.249142	-2.273591	0.836959
+2.072450	6.279575	0.462050	5.855829	-0.275256	-2.440263	0.834960
+2.073450	6.289151	1.113230	5.405749	-0.292309	-2.573095	0.836292
+2.074448	6.595588	1.486701	4.733023	-0.324685	-2.670887	0.844153
+2.075428	6.870903	1.809896	4.670778	-0.345602	-2.733905	0.859075
+2.076469	6.902026	1.848201	4.677960	-0.342538	-2.762417	0.868135
+2.077445	7.081579	1.936781	4.517559	-0.339074	-2.758819	0.874930
+2.078448	6.777536	2.238430	4.661202	-0.346002	-2.746562	0.873597
+2.079393	6.645863	2.449106	4.567834	-0.349066	-2.734038	0.861873
+2.080367	6.545313	2.779484	4.402645	-0.353596	-2.714320	0.849083
+2.081416	6.418429	2.887216	4.718659	-0.362123	-2.675816	0.834161
+2.082436	6.480674	2.978189	4.778510	-0.363322	-2.637446	0.820971
+2.083436	6.205359	2.796242	4.871877	-0.365320	-2.631717	0.796323
+2.084437	6.152690	2.932703	4.713871	-0.376245	-2.640243	0.758352
+2.085436	6.492645	2.994948	4.184787	-0.367851	-2.621191	0.720515
+2.086446	6.964271	2.803424	4.019598	-0.371848	-2.596677	0.689472
+2.087507	7.428715	2.496987	4.342794	-0.399427	-2.578691	0.667089
+2.088511	7.610663	2.104364	4.639655	-0.411951	-2.559639	0.646971
+2.089513	7.792610	1.790744	4.419403	-0.387969	-2.526064	0.624455
+2.090509	7.823732	1.295177	4.965245	-0.347734	-2.462113	0.597542
+2.091508	8.395909	1.122806	5.128040	-0.326949	-2.380709	0.563701
+2.092509	8.690376	1.187445	4.563046	-0.326550	-2.298905	0.527995
+2.093510	8.738257	0.981558	4.903000	-0.318423	-2.225628	0.493489
+2.094469	8.762197	0.703849	5.357868	-0.303368	-2.154882	0.462446
+2.095435	8.850777	0.560206	5.693034	-0.292176	-2.079207	0.433268
+2.096470	8.853171	0.433322	5.846253	-0.284715	-2.003798	0.402092
+2.097450	8.594614	0.351924	5.532633	-0.282983	-1.937982	0.369717
+2.098417	8.424637	0.284891	5.242954	-0.282583	-1.884822	0.336142
+2.099436	8.233114	0.313620	5.118464	-0.284449	-1.836326	0.300570
+2.100441	8.206779	0.457262	4.558258	-0.301369	-1.788496	0.267528
+2.101438	8.020044	0.490779	4.407433	-0.322020	-1.751591	0.238217
+2.102435	7.828521	0.536266	4.381099	-0.334144	-1.713487	0.210106
+2.103426	7.727971	0.600905	4.393069	-0.345735	-1.673384	0.182527
+2.104437	7.780640	0.749335	4.517559	-0.354928	-1.619159	0.158012
+2.105440	7.828521	0.916918	4.333218	-0.352397	-1.544150	0.133231
+2.106505	7.883583	1.058167	4.067479	-0.353995	-1.464345	0.110582
+2.107510	7.814156	1.060561	4.050721	-0.360657	-1.388669	0.087266
+2.108508	7.850067	1.110836	4.203939	-0.369051	-1.316325	0.063152
+2.109514	7.864431	1.225750	4.110572	-0.380109	-1.242914	0.037305
+2.110508	7.785428	1.357422	3.875956	-0.390501	-1.173900	0.009326
+2.111508	7.687272	1.271237	3.713161	-0.398761	-1.115812	-0.017187
+2.112470	7.780640	1.220962	3.689220	-0.404490	-1.065850	-0.043700
+2.113412	7.941041	1.247296	3.612611	-0.411685	-1.020818	-0.071279
+2.114400	8.087077	1.225750	3.610217	-0.417680	-0.981515	-0.100057
+2.115394	8.254660	1.247296	3.593458	-0.423809	-0.955668	-0.130034
+2.116402	8.448578	1.285601	3.591064	-0.432602	-0.928355	-0.160810
+2.117386	8.666436	1.453184	3.583882	-0.443127	-0.911035	-0.188789
+2.118449	8.841201	1.460366	3.686826	-0.452453	-0.895980	-0.218899
+2.119450	9.015966	1.584856	3.626975	-0.461779	-0.881591	-0.249675
+2.120447	9.166791	1.654284	3.756253	-0.472971	-0.864005	-0.283250
+2.121448	9.324797	1.714135	3.875956	-0.483763	-0.848550	-0.316957
+2.122448	9.504351	1.742863	3.911866	-0.493622	-0.835093	-0.349732
+2.123447	9.506745	1.716529	3.830469	-0.498685	-0.822037	-0.378776
+2.124430	9.466046	1.599221	3.828075	-0.502015	-0.810712	-0.404757
+2.125460	9.626447	1.481913	3.816104	-0.508810	-0.799387	-0.435400
+2.126449	9.645599	1.436426	3.890320	-0.517070	-0.789795	-0.470306
+2.127449	9.518715	1.443608	3.938201	-0.523199	-0.778870	-0.497885
+2.128448	9.533079	1.381363	3.947777	-0.527596	-0.772075	-0.520534
+2.129451	9.571384	1.278419	4.038750	-0.530260	-0.765280	-0.540119
+2.130392	9.614477	1.249690	4.077055	-0.534524	-0.761550	-0.559971
+2.131371	9.597718	1.082107	4.057903	-0.536389	-0.764881	-0.576625
+2.132370	9.650387	0.957617	4.213516	-0.536389	-0.775273	-0.587017
+2.133437	9.700662	0.859461	4.256608	-0.537055	-0.785665	-0.596210
+2.134444	10.028646	0.672726	4.359552	-0.532392	-0.786597	-0.606469
+2.135438	10.229746	0.466838	4.613321	-0.521334	-0.783000	-0.611798
+2.136445	10.217775	0.203494	4.948487	-0.506279	-0.786597	-0.612597
+2.137452	10.196229	-0.143643	5.027490	-0.483096	-0.791127	-0.600873
+2.138390	9.928096	-0.543448	5.142404	-0.456717	-0.812577	-0.580888
+2.139448	9.523503	-0.873826	5.084947	-0.432735	-0.844020	-0.559971
+2.140447	9.671934	-1.185051	4.986792	-0.408753	-0.859874	-0.539054
+2.141450	9.952037	-1.460366	5.003550	-0.383440	-0.856810	-0.516538
+2.142445	10.095679	-1.635131	4.986792	-0.358126	-0.852014	-0.492956
+2.143447	9.968795	-1.776380	4.857513	-0.339873	-0.890917	-0.464178
+2.144449	9.762907	-1.982268	4.572622	-0.314159	-0.927023	-0.436199
+2.145450	10.342266	-2.085211	4.385887	-0.286847	-0.941012	-0.399694
+2.146391	10.004706	-2.135486	4.405039	-0.266063	-0.952603	-0.372115
+2.147371	9.865851	-1.989450	4.081843	-0.252473	-0.980848	-0.343337
+2.148349	9.547443	-1.917628	3.928625	-0.237951	-0.998968	-0.315758
+2.149452	9.466046	-1.805108	4.057903	-0.222363	-1.018020	-0.292576
+2.150449	9.092575	-1.726105	4.136906	-0.204643	-1.020685	-0.272191
+2.151443	8.711922	-1.601615	4.230274	-0.186124	-1.036006	-0.254205
+2.152449	8.359998	-1.462760	4.213516	-0.166006	-1.044000	-0.237418
+2.153448	8.185233	-1.285601	4.077055	-0.146421	-1.039470	-0.217433
+2.154450	7.850067	-0.967193	4.002840	-0.131366	-1.038937	-0.200247
+2.155448	7.768669	-0.768488	3.660492	-0.117243	-1.041735	-0.183726
+2.156450	7.706424	-0.521901	3.318144	-0.102588	-1.034141	-0.168671
+2.157409	7.725577	-0.282497	3.186471	-0.084069	-1.015755	-0.152550
+2.158472	7.725577	-0.138854	3.042829	-0.063551	-1.000966	-0.135896
+2.159450	7.723183	-0.028729	2.863275	-0.039436	-0.994971	-0.119642
+2.160452	7.634603	0.074215	2.607113	-0.018919	-0.990974	-0.104320
+2.161431	7.416745	0.203494	2.398831	-0.000666	-1.001100	-0.090597
+2.162446	7.534053	0.292073	2.262371	0.021317	-1.010026	-0.073677
+2.163393	7.478990	0.311226	2.058877	0.045165	-1.004963	-0.061020
+2.164371	7.376046	0.351924	1.975085	0.067681	-1.012557	-0.053959
+2.165437	7.318589	0.409381	2.006208	0.089265	-1.021351	-0.052360
+2.166435	7.028910	0.378259	1.893688	0.110715	-1.044000	-0.053559
+2.167435	6.787112	0.299255	1.805108	0.128568	-1.078107	-0.051294
+2.168446	6.753595	0.296861	1.843413	0.140959	-1.119675	-0.041568
+2.169476	6.964271	0.457262	1.656678	0.153083	-1.164308	-0.025447
+2.170513	7.134248	0.538660	1.328694	0.167205	-1.214536	-0.007727
+2.171513	7.122278	0.610481	1.153929	0.178397	-1.271959	0.012524
+2.172509	7.182129	0.734971	1.122806	0.185458	-1.328315	0.035839
+2.173509	7.153400	0.775670	1.206598	0.177864	-1.369750	0.062352
+2.174508	7.447868	0.885796	1.424456	0.166672	-1.384006	0.091130
+2.175511	7.651361	1.015074	1.146747	0.157213	-1.383740	0.117910
+2.176508	7.474202	0.974375	1.101260	0.145355	-1.382807	0.143757
+2.177468	7.392805	1.017468	1.206598	0.135230	-1.377078	0.169470
+2.178509	7.383229	1.144353	1.252084	0.122440	-1.367086	0.192919
+2.179442	7.323377	1.266449	1.359816	0.108983	-1.362023	0.214502
+2.180445	7.210857	1.182657	1.309542	0.091796	-1.368951	0.235020
+2.181437	7.182129	1.146747	1.335876	0.072611	-1.392133	0.258868
+2.182437	7.344924	1.115624	1.316724	0.048096	-1.425441	0.283516
+2.183438	7.704030	1.086896	1.204204	0.027312	-1.450755	0.309763
+2.184438	8.094259	1.024650	1.498671	0.005596	-1.472072	0.334277
+2.185438	8.525187	0.967193	1.400515	-0.020651	-1.491923	0.354528
+2.186438	8.913022	0.696667	1.639919	-0.057689	-1.516704	0.364254
+2.187438	9.135668	0.450080	1.807502	-0.096593	-1.554276	0.370383
+2.188431	9.387042	0.232222	1.869748	-0.141891	-1.606103	0.376778
+2.189387	9.695874	0.004788	1.850595	-0.171469	-1.658329	0.388502
+2.190407	9.688692	-0.488385	2.485017	-0.171735	-1.694035	0.399161
+2.191455	10.105255	-0.854673	2.894398	-0.176132	-1.719083	0.407155
+2.192454	10.112437	-0.940859	2.432348	-0.170270	-1.723613	0.420744
+2.193457	9.990341	-1.108442	2.683722	-0.175599	-1.724812	0.432469
+2.194450	10.189047	-1.194627	2.358132	-0.201979	-1.744930	0.439930
+2.195450	9.980765	-1.199416	2.291099	-0.234887	-1.783034	0.449922
+2.196395	9.959219	-1.146747	2.300675	-0.248743	-1.807415	0.472971
+2.197390	9.882609	-1.201810	2.571202	-0.245812	-1.803152	0.498685
+2.198375	9.806000	-1.015074	2.580778	-0.238484	-1.792093	0.518136
+2.199374	9.664751	-0.785246	2.544868	-0.242481	-1.794092	0.529594
+2.200458	9.568990	-0.562600	2.279129	-0.262466	-1.804217	0.542251
+2.201460	9.456470	-0.143643	2.252794	-0.298038	-1.817008	0.557972
+2.202454	9.401407	0.287285	1.771592	-0.327349	-1.819406	0.569164
+2.203454	8.989631	0.485991	1.891294	-0.330147	-1.799288	0.574760
+2.204454	8.889082	0.679908	2.391649	-0.335876	-1.783700	0.572228
+2.205452	8.776562	1.062955	2.176185	-0.349599	-1.760917	0.565833
+2.206454	8.585038	1.402909	1.881718	-0.383173	-1.738268	0.555308
+2.207450	8.637707	1.685406	1.350240	-0.431270	-1.715352	0.547580
+2.208426	8.654465	1.814685	1.378969	-0.456850	-1.676582	0.539453
+2.209450	8.668830	1.793138	1.589645	-0.446058	-1.608634	0.526397
+2.210455	8.759803	1.864959	1.580068	-0.436732	-1.531227	0.506945
+2.211455	8.731075	2.085211	1.484307	-0.448856	-1.460881	0.482564
+2.212455	8.788532	2.192943	1.106048	-0.468175	-1.400394	0.458449
+2.213441	8.740651	2.111546	1.089290	-0.475103	-1.342305	0.431270
+2.214435	8.898658	2.058877	0.950435	-0.470173	-1.281818	0.396629
+2.215418	9.047088	1.941569	1.050985	-0.456184	-1.218000	0.364521
+2.216403	9.159608	1.764410	1.292783	-0.445259	-1.161643	0.333078
+2.217435	9.274522	1.683012	1.137170	-0.434467	-1.111681	0.298305
+2.218435	9.456470	1.601615	1.151535	-0.421277	-1.059988	0.257669
+2.219436	9.774877	1.599221	1.139564	-0.409020	-1.001366	0.212770
+2.220436	10.133984	1.575280	1.220962	-0.400360	-0.940746	0.170003
+2.221482	10.361418	1.558522	1.223356	-0.395430	-0.872132	0.124971
+2.222514	10.382964	1.532187	1.216174	-0.387303	-0.806848	0.077407
+2.223510	10.363812	1.366999	1.211386	-0.378776	-0.750225	0.029844
+2.224509	10.260868	1.220962	1.175475	-0.372115	-0.706525	-0.017587
+2.225510	10.212987	1.055773	1.096472	-0.366519	-0.674017	-0.063951
+2.226442	10.047798	0.892978	1.065349	-0.362922	-0.648969	-0.106851
+2.227509	9.846699	0.754124	0.924101	-0.363588	-0.635247	-0.149352
+2.228518	9.676722	0.742153	0.790034	-0.363721	-0.624721	-0.187723
+2.229457	9.451682	0.701455	0.802004	-0.363322	-0.615662	-0.219698
+2.230462	9.241006	0.665544	0.734971	-0.363055	-0.602738	-0.250874
+2.231423	9.061453	0.699061	0.730183	-0.366119	-0.588749	-0.280185
+2.232437	8.841201	0.655968	0.687090	-0.368651	-0.575292	-0.308031
+2.233397	8.678406	0.679908	0.639209	-0.369850	-0.561170	-0.333611
+2.234396	8.589826	0.727789	0.651180	-0.372914	-0.547580	-0.356260
+2.235396	8.549127	0.876220	0.629633	-0.379443	-0.533991	-0.376911
+2.236477	8.649677	1.041409	0.588935	-0.389168	-0.523599	-0.393965
+2.237476	8.867535	1.118018	0.655968	-0.401026	-0.518403	-0.411951
+2.238490	9.068635	1.182657	0.572176	-0.418080	-0.515072	-0.431270
+2.239420	9.384648	1.177869	0.624845	-0.440995	-0.514672	-0.448856
+2.240462	9.777271	1.163505	0.677514	-0.467508	-0.519202	-0.466443
+2.241478	10.095679	1.031833	0.634421	-0.497219	-0.526663	-0.486028
+2.242476	10.428451	0.723001	0.763700	-0.524265	-0.539320	-0.506945
+2.243476	10.660673	0.387835	0.876220	-0.550378	-0.554508	-0.527196
+2.244478	10.861773	0.169977	0.778064	-0.576358	-0.570230	-0.547847
+2.245477	10.940776	-0.081397	0.883402	-0.601406	-0.583420	-0.568231
+2.246420	10.979081	-0.306437	0.797216	-0.624988	-0.598874	-0.585818
+2.247396	10.888107	-0.517113	0.682302	-0.644573	-0.609799	-0.594345
+2.248397	10.691796	-0.732577	0.502749	-0.662026	-0.623123	-0.596210
+2.249419	10.449998	-0.782852	0.371077	-0.678680	-0.637112	-0.589948
+2.250405	10.133984	-0.833127	0.418958	-0.690404	-0.649236	-0.578090
+2.251417	9.691086	-0.859461	0.311226	-0.703594	-0.666956	-0.561969
+2.252505	9.320009	-0.828339	0.275315	-0.716917	-0.686141	-0.544916
+2.253504	8.965691	-0.749335	0.213070	-0.728775	-0.701729	-0.527462
+2.254502	8.585038	-0.679908	0.344742	-0.736769	-0.715585	-0.509743
+2.255501	8.118200	-0.605693	0.404593	-0.739034	-0.727842	-0.489625
+2.256499	7.706424	-0.526689	0.488385	-0.733971	-0.735037	-0.467109
+2.257501	7.411957	-0.445292	0.474021	-0.721714	-0.730773	-0.442861
+2.258501	7.014546	-0.474021	0.569782	-0.701596	-0.723979	-0.417413
+2.259441	6.660228	-0.474021	0.675120	-0.673884	-0.714119	-0.392632
+2.260477	6.454340	-0.478809	0.713425	-0.640043	-0.701729	-0.365986
+2.261507	6.435187	-0.469232	0.706243	-0.599274	-0.686407	-0.334943
+2.262501	6.349002	-0.414169	0.670332	-0.553309	-0.671485	-0.302168
+2.263436	6.380125	-0.287285	0.548236	-0.507211	-0.655098	-0.268861
+2.264426	6.483068	-0.146037	0.519507	-0.462845	-0.641375	-0.239150
+2.265438	6.720079	-0.014364	0.445292	-0.421943	-0.629251	-0.207841
+2.266435	7.093549	0.201100	0.426140	-0.383306	-0.620458	-0.173334
+2.267436	7.481384	0.327984	0.289679	-0.349599	-0.608201	-0.142025
+2.268435	7.878795	0.450080	0.294467	-0.321620	-0.594078	-0.112580
+2.269437	8.297753	0.524295	0.316014	-0.299904	-0.582887	-0.086734
+2.270437	8.673618	0.483597	0.423746	-0.280985	-0.575825	-0.061686
+2.271484	9.027936	0.426140	0.404593	-0.265930	-0.572095	-0.042234
+2.272511	9.375072	0.488385	0.354318	-0.250874	-0.573560	-0.020651
+2.273513	9.664751	0.490779	0.395017	-0.232888	-0.578623	0.001599
+2.274509	9.995129	0.541054	0.327984	-0.212637	-0.590614	0.021850
+2.275510	10.303961	0.517113	0.239404	-0.190254	-0.607401	0.043167
+2.276509	10.531395	0.564994	0.217858	-0.168804	-0.623522	0.061286
+2.277510	10.608004	0.663150	0.239404	-0.149219	-0.641375	0.075809
+2.278520	10.588852	0.790034	0.445292	-0.133098	-0.662292	0.090331
+2.279449	10.634339	0.950435	0.670332	-0.120175	-0.678680	0.106052
+2.280444	10.694190	1.096472	0.794822	-0.110449	-0.692136	0.117776
+2.281394	10.902472	1.264055	0.888190	-0.110848	-0.712787	0.122839
+2.282405	11.182575	1.376575	0.950435	-0.114845	-0.739966	0.123905
+2.283405	11.354946	1.345452	1.058167	-0.112714	-0.767279	0.122972
+2.284405	11.230456	1.017468	1.118018	-0.108450	-0.810712	0.110182
+2.285402	10.581670	0.433322	1.216174	-0.108051	-0.904374	0.080205
+2.286446	9.997523	-0.134066	1.529793	-0.116178	-1.057856	0.059954
+2.287449	10.734889	-0.241798	1.115624	-0.128701	-1.229191	0.067815
+2.288448	11.522529	0.004788	0.162795	-0.144822	-1.384406	0.086067
+2.289458	11.378886	0.179553	-0.179553	-0.162809	-1.524299	0.100057
+2.290430	11.340582	0.462050	-0.186735	-0.187456	-1.651268	0.112447
+2.291450	11.345370	0.596117	-0.131672	-0.207841	-1.737069	0.131233
+2.292449	11.235244	0.861855	0.021546	-0.221430	-1.785698	0.145888
+2.293451	10.713342	0.928889	0.074215	-0.253139	-1.842721	0.159345
+2.294445	10.011888	1.067743	0.153219	-0.284582	-1.880292	0.188123
+2.295449	9.633629	1.287995	0.248980	-0.306698	-1.895747	0.223296
+2.296449	9.286493	1.129988	0.469232	-0.332812	-1.919862	0.258202
+2.297443	8.936962	1.043803	0.497961	-0.372914	-1.956634	0.297905
+2.298414	8.793320	1.156323	0.052669	-0.391966	-1.976752	0.340939
+2.299439	8.376756	0.766094	0.234616	-0.414083	-1.994738	0.383706
+2.300435	8.379150	0.588935	0.445292	-0.441395	-2.022450	0.429671
+2.301438	8.077501	0.392623	0.567388	-0.463511	-2.072279	0.471372
+2.302435	8.051167	0.438110	0.203494	-0.470306	-2.125305	0.497619
+2.303437	8.245084	0.521901	-0.167583	-0.481098	-2.154616	0.513740
+2.304442	8.448578	0.612875	-0.301649	-0.499084	-2.174867	0.531859
+2.305510	8.723893	0.591329	0.040699	-0.527862	-2.198848	0.548113
+2.306509	8.951327	0.694272	-0.277709	-0.564501	-2.233622	0.550245
+2.307509	8.687982	0.976770	-1.010286	-0.573960	-2.235087	0.557972
+2.308461	8.731075	1.031833	-0.423746	-0.563035	-2.204311	0.567698
+2.309462	8.913022	1.242508	-0.371077	-0.577691	-2.186458	0.573161
+2.310508	8.508429	1.347846	-0.689484	-0.589015	-2.192986	0.575159
+2.311509	8.280995	1.153929	-0.272921	-0.589015	-2.204044	0.571429
+2.312511	8.467730	1.316724	-0.459656	-0.602738	-2.196450	0.565300
+2.313413	8.659253	1.606403	-1.113230	-0.637778	-2.190188	0.566499
+2.314402	8.565886	1.484307	-0.572176	-0.669487	-2.182461	0.570629
+2.315405	8.443790	1.295177	-0.421352	-0.662959	-2.170204	0.552243
+2.316406	8.034408	1.479519	-1.048591	-0.656697	-2.132366	0.534923
+2.317406	8.582644	1.563310	-0.883402	-0.680279	-2.084936	0.529461
+2.318424	8.527581	1.733287	-1.302359	-0.712920	-2.056291	0.513473
+2.319431	7.720789	1.570492	-1.781168	-0.717983	-2.040969	0.489225
+2.320483	7.653755	1.213780	-1.125200	-0.694401	-2.009926	0.459914
+2.321491	7.811762	1.323906	-1.125200	-0.684009	-1.966893	0.427539
+2.322485	7.931464	1.484307	-1.908052	-0.683343	-1.929455	0.390501
+2.323488	7.768669	1.429244	-2.173791	-0.655231	-1.894015	0.350931
+2.324487	7.929070	1.036621	-1.472336	-0.604470	-1.816342	0.310429
+2.325488	8.527581	0.986346	-1.613585	-0.587017	-1.730807	0.270459
+2.326487	8.307329	1.082107	-2.180973	-0.576225	-1.658995	0.230890
+2.327440	7.909918	0.988740	-1.955933	-0.521867	-1.573594	0.188256
+2.328444	8.295359	0.720607	-1.352634	-0.463911	-1.477268	0.140825
+2.329489	8.872323	0.904948	-1.867354	-0.418613	-1.364954	0.099790
+2.330432	9.061453	1.017468	-2.178579	-0.378377	-1.243847	0.064217
+2.331406	9.205095	0.950435	-1.898476	-0.339873	-1.135530	0.029178
+2.332404	9.162002	0.825945	-1.582462	-0.298038	-1.022550	-0.001732
+2.333406	9.324797	0.802004	-1.493883	-0.260201	-0.912900	-0.031709
+2.334405	9.408589	0.773276	-1.393333	-0.225827	-0.814443	-0.059554
+2.335406	9.365496	0.823551	-1.446002	-0.201446	-0.723579	-0.087133
+2.336487	9.363102	0.924101	-1.544158	-0.182926	-0.641908	-0.111248
+2.337488	9.384648	0.837915	-1.474730	-0.167605	-0.570230	-0.131233
+2.338430	9.442105	0.804398	-1.486701	-0.155614	-0.506945	-0.150818
+2.339446	9.439711	0.818763	-1.656678	-0.149352	-0.453386	-0.170936
+2.340488	9.442105	0.845097	-1.826655	-0.145888	-0.410752	-0.190387
+2.341491	9.554625	0.890584	-1.793138	-0.146688	-0.380908	-0.208374
+2.342457	9.602506	0.871432	-1.848201	-0.149885	-0.357326	-0.226760
+2.343488	9.636023	0.790034	-1.752439	-0.154815	-0.339074	-0.243014
+2.344487	9.691086	0.761306	-1.692588	-0.161476	-0.326417	-0.258735
+2.345488	9.810788	0.689484	-1.637525	-0.167472	-0.318156	-0.269260
+2.346429	9.911338	0.699061	-1.608797	-0.176931	-0.307498	-0.282450
+2.347405	9.999917	0.541054	-1.472336	-0.187856	-0.298704	-0.294974
+2.348409	10.126802	0.466838	-1.366999	-0.199980	-0.292043	-0.303501
+2.349427	10.241716	0.316014	-1.295177	-0.210639	-0.285781	-0.311361
+2.350420	10.327901	0.191523	-1.299965	-0.218100	-0.279119	-0.316557
+2.351422	10.507455	0.057457	-1.333482	-0.220364	-0.275522	-0.321620
+2.352428	10.526607	0.004788	-1.438820	-0.221164	-0.292975	-0.326550
+2.353512	10.631945	-0.004788	-1.694982	-0.219565	-0.331613	-0.319489
+2.354451	10.507455	-0.076609	-1.943963	-0.205576	-0.354928	-0.306032
+2.355425	10.445209	-0.064639	-2.046907	-0.186524	-0.350931	-0.294574
+2.356431	10.196229	-0.095762	-1.862565	-0.168671	-0.339606	-0.283250
+2.357380	9.906550	-0.055063	-1.783562	-0.158678	-0.335876	-0.273790
+2.358375	9.817970	0.229828	-1.896082	-0.155214	-0.334011	-0.264464
+2.359379	9.748543	0.392623	-1.886506	-0.151484	-0.321887	-0.253273
+2.360378	9.674328	0.603299	-1.771592	-0.148153	-0.303368	-0.241815
+2.361382	9.583354	0.866644	-1.656678	-0.145888	-0.286447	-0.231156
+2.362382	9.504351	1.046197	-1.637525	-0.149352	-0.271792	-0.221830
+2.363380	9.485198	1.022256	-1.639919	-0.156680	-0.255671	-0.214636
+2.364379	9.434923	0.940859	-1.465154	-0.163208	-0.239683	-0.210772
+2.365382	9.391831	0.974375	-1.465154	-0.167338	-0.226760	-0.210239
+2.366380	9.540261	1.041409	-1.694982	-0.162809	-0.222363	-0.207441
+2.367455	9.796424	1.134776	-1.891294	-0.151617	-0.221430	-0.202778
+2.368456	9.952037	1.134776	-2.027754	-0.140959	-0.219965	-0.205975
+2.369456	9.947249	1.158717	-2.087605	-0.131100	-0.220897	-0.214902
+2.370426	9.849093	1.180263	-2.015784	-0.121507	-0.219299	-0.224761
+2.371484	9.825152	1.208992	-1.946357	-0.109383	-0.214369	-0.232089
+2.372456	9.703056	1.201810	-1.831443	-0.096060	-0.211704	-0.238750
+2.373458	9.597718	1.280813	-1.888900	-0.083936	-0.208107	-0.248343
+2.374457	9.573778	1.256873	-1.953539	-0.073277	-0.200913	-0.256470
+2.375459	9.466046	1.235326	-1.965509	-0.062885	-0.187723	-0.265130
+2.376456	9.308039	1.218568	-2.018178	-0.051427	-0.172135	-0.271792
+2.377455	9.157214	1.175475	-1.963115	-0.038237	-0.158678	-0.277121
+2.378456	9.015966	1.050985	-1.884112	-0.023982	-0.144822	-0.279119
+2.379387	8.862747	0.967193	-1.876930	-0.010126	-0.134564	-0.281917
+2.380381	8.802896	0.845097	-2.034937	0.005862	-0.130433	-0.285648
+2.381407	8.838807	0.687090	-2.166609	0.027979	-0.121640	-0.287779
+2.382406	8.836413	0.605693	-2.135486	0.052227	-0.113646	-0.285914
+2.383401	8.678406	0.562600	-2.037331	0.074609	-0.123372	-0.286714
+2.384491	8.850777	0.471626	-2.164215	0.094727	-0.132165	-0.286847
+2.385491	9.063847	0.411775	-2.147457	0.122839	-0.126969	-0.285515
+2.386487	9.293675	0.363895	-2.082817	0.156014	-0.114579	-0.283383
+2.387491	9.444500	0.327984	-2.113940	0.185724	-0.107384	-0.283250
+2.388486	9.506745	0.318408	-2.075635	0.211438	-0.106851	-0.283250
+2.389428	9.609688	0.320802	-1.900870	0.237152	-0.106185	-0.281784
+2.390432	9.652781	0.349530	-1.867354	0.258735	-0.110449	-0.279786
+2.391486	9.944854	0.323196	-1.948751	0.278587	-0.114845	-0.281784
+2.392480	10.177077	0.260951	-1.960721	0.301769	-0.114179	-0.281118
+2.393490	10.308749	0.201100	-1.931993	0.327749	-0.113779	-0.277121
+2.394488	10.165106	0.076609	-1.953539	0.351198	-0.131366	-0.275522
+2.395486	10.208199	-0.071821	-2.006208	0.370649	-0.157080	-0.274590
+2.396473	10.315931	-0.131672	-2.073241	0.390101	-0.175599	-0.270859
+2.397451	10.402117	-0.220252	-1.996632	0.407688	-0.182926	-0.264864
+2.398438	10.493090	-0.332772	-1.955933	0.424475	-0.187323	-0.257669
+2.399433	10.435633	-0.354318	-1.931993	0.439530	-0.189855	-0.247011
+2.400433	10.351842	-0.469232	-1.762016	0.453386	-0.193718	-0.234354
+2.401437	10.186653	-0.543448	-1.656678	0.464577	-0.200779	-0.220098
+2.402439	10.023858	-0.514719	-1.589645	0.470173	-0.208640	-0.203311
+2.403411	9.937672	-0.512325	-1.553734	0.471372	-0.215168	-0.182926
+2.404415	9.875427	-0.452474	-1.584856	0.469507	-0.220498	-0.162009
+2.405358	9.748543	-0.316014	-1.592039	0.465776	-0.227292	-0.138028
+2.406397	9.585748	-0.265739	-1.637525	0.463245	-0.235553	-0.110315
+2.407449	9.449288	-0.198706	-1.644708	0.460980	-0.246345	-0.081138
+2.408448	9.358314	-0.186735	-1.613585	0.456983	-0.255138	-0.051694
+2.409406	9.267340	-0.146037	-1.659072	0.450988	-0.262066	-0.023049
+2.410368	9.162002	-0.086186	-1.649496	0.443260	-0.266729	0.003597
+2.411449	9.051876	-0.093368	-1.666254	0.437398	-0.272458	0.028911
+2.412448	9.006390	-0.083792	-1.783562	0.433801	-0.277387	0.050894
+2.413382	9.006390	-0.035911	-1.733287	0.427139	-0.280319	0.068747
+2.414370	8.975267	0.009576	-1.726105	0.419412	-0.281651	0.086467
+2.415379	8.953721	0.038305	-1.702165	0.413683	-0.282983	0.101256
+2.416450	8.917810	0.038305	-1.785956	0.407954	-0.285515	0.113247
+2.417449	8.874717	0.062245	-1.800320	0.400893	-0.287113	0.121240
+2.418448	8.805290	0.050275	-1.893688	0.394231	-0.288845	0.128835
+2.419450	8.783744	0.100550	-2.044513	0.385571	-0.288312	0.136162
+2.420404	8.759803	0.134066	-2.113940	0.378910	-0.288312	0.144556
+2.421471	8.731075	0.174765	-2.109152	0.373847	-0.286580	0.152417
+2.422450	8.676012	0.203494	-2.104364	0.368784	-0.284315	0.158012
+2.423444	8.683194	0.203494	-2.204914	0.361190	-0.281518	0.162276
+2.424450	8.690376	0.234616	-2.259977	0.355194	-0.279119	0.163475
+2.425451	8.640101	0.246586	-2.226460	0.352263	-0.279253	0.161476
+2.426448	8.606584	0.220252	-2.121122	0.350531	-0.278986	0.161077
+2.427400	8.508429	0.169977	-2.130698	0.347067	-0.278187	0.158678
+2.428449	8.443790	0.129278	-2.281523	0.344936	-0.277254	0.156680
+2.429451	8.410273	0.112520	-2.420377	0.342937	-0.272724	0.154149
+2.430391	8.359998	0.131672	-2.523321	0.341472	-0.269527	0.150152
+2.431381	8.194809	0.119702	-2.525715	0.337075	-0.267662	0.146421
+2.432369	8.060743	0.057457	-2.508957	0.332545	-0.265930	0.143757
+2.433452	7.988921	0.035911	-2.578384	0.328681	-0.264064	0.140959
+2.434449	7.967375	0.014364	-2.633447	0.326550	-0.261000	0.140159
+2.435449	7.909918	0.050275	-2.513745	0.326017	-0.260867	0.138161
+2.436443	7.854855	0.009576	-2.494593	0.323219	-0.259801	0.135096
+2.437448	7.960193	0.045487	-2.506563	0.318556	-0.257536	0.131366
+2.438449	8.099047	0.033517	-2.470652	0.312028	-0.256603	0.124838
+2.439447	8.249872	0.040699	-2.377285	0.306832	-0.259401	0.113779
+2.440450	8.518005	0.057457	-2.288705	0.298038	-0.261400	0.100057
+2.441428	8.654465	-0.045487	-2.202520	0.281384	-0.267395	0.081671
+2.442430	8.573068	-0.239404	-2.063665	0.255271	-0.301236	0.048629
+2.443449	7.313801	-1.189839	-1.316724	0.198248	-0.433934	-0.010259
+2.444448	5.391385	-2.963825	0.524295	0.130034	-0.785931	-0.069547
+2.445451	5.597272	-3.919048	1.053379	0.128568	-1.234121	-0.145222
+2.446391	5.293229	-2.396437	-2.216884	0.170536	-1.459815	-0.223962
+2.447372	7.167765	-0.914524	-6.724867	0.160011	-1.532026	-0.262066
+2.448370	9.985553	-0.454868	-6.708108	0.083936	-1.624355	-0.257936
+2.449441	10.993445	-0.809187	-4.302095	-0.032642	-1.801286	-0.249142
+2.450450	11.524923	-1.113230	-3.050011	-0.114712	-1.955168	-0.242747
+2.451428	12.051612	-1.137170	-1.525005	-0.125770	-1.990741	-0.252340
+2.452429	11.532105	-0.651180	-1.833837	-0.108983	-1.916132	-0.297106
+2.453449	10.679826	0.093368	-3.255898	-0.127902	-1.819806	-0.318689
+2.454449	10.473938	-0.019152	-1.891294	-0.140825	-1.740133	-0.276055
+2.455448	11.096389	-0.325590	0.102944	-0.184792	-1.716418	-0.221697
+2.456448	11.012598	-0.150825	-0.428534	-0.196916	-1.675516	-0.173201
+2.457449	9.956825	0.095762	-1.168293	-0.148953	-1.553876	-0.174533
+2.458443	8.728681	0.478809	-3.028464	-0.116844	-1.399861	-0.188655
+2.459449	8.831625	0.986346	-3.246322	-0.142824	-1.307398	-0.148686
+2.460450	8.747833	0.371077	-1.015074	-0.148553	-1.240116	-0.105119
+2.461439	8.597008	0.320802	-1.034227	-0.169204	-1.181495	-0.069280
+2.462469	8.879505	0.641604	-1.345452	-0.227692	-1.144856	-0.021717
+2.463391	9.241006	0.845097	-1.491489	-0.292709	-1.123806	0.013190
+2.464372	9.047088	0.708637	-1.517823	-0.330547	-1.091297	0.037704
+2.465433	9.592930	0.763700	-2.015784	-0.347867	-1.035473	0.047830
+2.466435	8.642495	0.845097	-2.731603	-0.335343	-0.974853	0.044233
+2.467435	8.364786	1.029438	-2.789060	-0.316025	-0.952204	0.043433
+2.468438	8.640101	0.955223	-2.961431	-0.291910	-0.924758	0.049828
+2.469510	8.853171	1.108442	-3.057193	-0.259801	-0.862672	0.051960
+2.470509	8.889082	1.249690	-3.164925	-0.229025	-0.778204	0.053559
+2.471438	8.786138	1.398121	-3.303779	-0.202245	-0.712387	0.049162
+2.472506	8.541945	1.388545	-3.473756	-0.172534	-0.662159	0.044899
+2.473513	8.711922	1.491489	-3.717949	-0.145622	-0.618326	0.041568
+2.474509	8.723893	1.570492	-3.878350	-0.117377	-0.571162	0.046098
+2.475508	8.917810	1.608797	-3.401935	-0.084735	-0.537588	0.049162
+2.476511	8.872323	1.582462	-3.389965	-0.053692	-0.527862	0.042101
+2.477510	8.683194	1.699771	-3.665280	-0.025447	-0.525997	0.031176
+2.478509	9.085393	1.776380	-3.698796	-0.020917	-0.532525	0.025447
+2.479447	9.367890	1.773986	-3.787376	-0.009593	-0.530527	0.015988
+2.480427	9.130880	1.723711	-3.806528	0.005462	-0.529994	0.000533
+2.481430	9.176367	1.527399	-3.674856	0.017453	-0.535323	-0.017986
+2.482412	8.915416	1.474730	-3.665280	0.028112	-0.531859	-0.034240
+2.483425	8.503641	1.340664	-3.607823	0.046364	-0.521467	-0.062352
+2.484430	7.943435	1.352634	-3.801740	0.065017	-0.521201	-0.086467
+2.485422	8.170869	1.266449	-3.418693	0.087133	-0.524531	-0.099257
+2.486425	8.225932	1.185051	-3.306173	0.126969	-0.498818	-0.120175
+2.487425	7.742335	1.364604	-4.103390	0.168271	-0.444992	-0.139493
+2.488509	7.783034	1.355028	-4.311671	0.207041	-0.403158	-0.152283
+2.489513	8.099047	1.192233	-3.988476	0.262066	-0.365187	-0.157479
+2.490451	8.269024	1.074925	-4.122542	0.336409	-0.305366	-0.155348
+2.491493	8.307329	1.029438	-4.654020	0.486028	-0.138161	-0.188789
+2.492514	6.607559	1.287995	-7.862037	0.602472	0.052493	-0.184925
+2.493512	8.841201	1.800320	-4.053115	0.560371	0.000000	-0.120974
+2.494510	10.766011	-0.023940	0.550630	0.498152	-0.134830	-0.094461
+2.495509	10.394935	0.148431	-0.957617	0.498685	-0.171069	-0.122306
+2.496477	9.298463	0.636815	-4.412221	0.547980	-0.105119	-0.146155
+2.497418	9.082999	0.950435	-5.642759	0.620325	-0.008926	-0.147887
+2.498404	8.946539	1.029438	-5.795978	0.721181	0.101789	-0.152949
+2.499405	8.027226	0.854673	-8.477306	0.961397	0.367319	-0.175865
+2.500406	8.395909	2.140274	-8.941750	1.005496	0.437798	-0.110715
+2.501368	11.608714	0.675120	0.612875	0.874530	0.242481	-0.041302
+2.502452	12.001337	-0.466838	2.185761	0.859342	0.161609	-0.079939
+2.503449	9.645599	0.366289	-6.708108	1.057323	0.418879	-0.170136
+2.504449	8.577856	1.829049	-11.893605	1.227060	0.693202	-0.162942
+2.505448	9.971189	1.513035	-5.568544	1.236519	0.697332	-0.086600
+2.506449	11.493800	0.632027	1.457972	1.093162	0.450322	-0.027446
+2.507451	11.450708	-0.562600	1.532187	1.092230	0.376378	-0.078606
+2.508416	9.985553	0.485991	-6.320273	1.153516	0.491757	-0.127103
+2.509449	10.303961	1.129988	-4.591774	1.120741	0.499351	-0.114446
+2.510442	11.199333	0.502749	-0.555418	1.040669	0.419678	-0.088466
+2.511416	11.388462	0.562600	-0.430928	0.961930	0.362123	-0.090864
+2.512445	10.959929	0.962405	-1.146747	0.861473	0.310429	-0.093262
+2.513391	10.914442	0.979164	-0.682302	0.773940	0.263531	-0.096859
+2.514373	10.531395	0.950435	-1.747651	0.758619	0.284848	-0.106452
+2.515361	10.119620	1.268843	-3.672462	0.749692	0.335476	-0.101389
+2.516416	10.493090	1.326300	-2.180973	0.658828	0.293109	-0.071545
+2.517460	10.919230	1.395727	1.639919	0.484296	0.130433	-0.038104
+2.518448	10.794740	1.127594	2.657388	0.330280	-0.014789	-0.027979
+2.519451	10.169895	1.465154	-0.050275	0.240616	-0.068481	-0.038637
+2.520447	9.798818	1.857777	-2.506563	0.195583	-0.054358	-0.046764
+2.521435	9.688692	2.022966	-3.148167	0.169737	-0.024248	-0.046098
+2.522469	9.710238	1.903264	-2.760332	0.148953	-0.006928	-0.044366
+2.523444	9.767695	1.735681	-2.556838	0.133498	0.001199	-0.044766
+2.524448	9.837123	1.560916	-2.729209	0.126037	0.009593	-0.045965
+2.525449	10.038222	1.314330	-3.030858	0.127636	0.024648	-0.045965
+2.526448	10.184259	1.079713	-3.258292	0.134830	0.045165	-0.046098
+2.527411	10.265656	0.852279	-3.289415	0.146288	0.059688	-0.047564
+2.528379	10.169895	0.703849	-3.337296	0.159478	0.059155	-0.048896
+2.529382	10.102861	0.576964	-3.368418	0.169870	0.046897	-0.050761
+2.530370	10.148348	0.428534	-3.399541	0.176665	0.031842	-0.054891
+2.531369	10.201017	0.399805	-3.325326	0.182127	0.020917	-0.065949
+2.532398	10.330295	0.418958	-3.320538	0.185058	0.017853	-0.077541
+2.533424	10.327901	0.483597	-3.320538	0.184658	0.023449	-0.086867
+2.534450	10.363812	0.524295	-3.181683	0.183060	0.033841	-0.097925
+2.535449	10.277626	0.555418	-3.033252	0.181194	0.048096	-0.107651
+2.536442	10.193835	0.636815	-3.040435	0.179462	0.062352	-0.114046
+2.537445	10.122014	0.576964	-3.052405	0.177331	0.076741	-0.118842
+2.538448	10.004706	0.562600	-2.985372	0.175066	0.090730	-0.121907
+2.539411	9.916126	0.639209	-2.877640	0.172534	0.103920	-0.125637
+2.540448	9.868245	0.576964	-2.908762	0.169737	0.116577	-0.127636
+2.541446	9.806000	0.485991	-3.069163	0.165207	0.127636	-0.126836
+2.542430	9.686298	0.457262	-3.081133	0.160810	0.135096	-0.127369
+2.543404	9.535473	0.433322	-3.004524	0.157080	0.142158	-0.127103
+2.544443	9.470834	0.402199	-3.035646	0.153616	0.150152	-0.126170
+2.545446	9.394225	0.378259	-3.009312	0.150418	0.155348	-0.125770
+2.546387	9.293675	0.301649	-2.985372	0.148286	0.160277	-0.125104
+2.547370	9.217065	0.172371	-3.016494	0.146021	0.166139	-0.124172
+2.548370	9.185943	0.155613	-3.052405	0.145089	0.171868	-0.125504
+2.549439	9.138062	0.167583	-3.069163	0.144423	0.177597	-0.127369
+2.550438	9.102151	0.184341	-3.054799	0.143757	0.183593	-0.128968
+2.551508	9.032724	0.167583	-2.997342	0.143090	0.190654	-0.130167
+2.552510	8.996813	0.208282	-2.923126	0.141625	0.198381	-0.132032
+2.553463	9.111728	0.260951	-3.050011	0.140426	0.205975	-0.136162
+2.554490	9.032724	0.248980	-3.076345	0.138694	0.214502	-0.142158
+2.555510	8.948933	0.272921	-2.994948	0.138427	0.225028	-0.146954
+2.556509	8.939356	0.320802	-2.954249	0.137894	0.236885	-0.152150
+2.557513	8.896264	0.301649	-3.018888	0.137894	0.251141	-0.160011
+2.558510	8.776562	0.327984	-2.961431	0.137761	0.268328	-0.165740
+2.559510	8.635313	0.361500	-3.030858	0.134164	0.288712	-0.174933
+2.560510	8.568280	0.399805	-3.021282	0.129900	0.308830	-0.183193
+2.561441	8.467730	0.519507	-3.109862	0.125237	0.330280	-0.189855
+2.562467	8.319299	0.502749	-3.064375	0.120974	0.351198	-0.194251
+2.563464	8.156504	0.519507	-3.057193	0.116577	0.372648	-0.198914
+2.564443	8.003286	0.560206	-3.169713	0.113779	0.396363	-0.201712
+2.565439	7.835703	0.572176	-3.265475	0.108717	0.418213	-0.201446
+2.566437	7.629815	0.598511	-3.200835	0.105119	0.436732	-0.201579
+2.567437	7.452656	0.639209	-3.291809	0.100057	0.453519	-0.198115
+2.568437	7.261132	0.672726	-3.327720	0.093928	0.469907	-0.192652
+2.569434	7.179735	0.665544	-3.291809	0.087799	0.487227	-0.186923
+2.570419	7.107914	0.679908	-3.200835	0.078340	0.504014	-0.182527
+2.571437	7.019334	0.691878	-3.241534	0.067415	0.519469	-0.179329
+2.572463	7.069609	0.727789	-3.205624	0.055957	0.535323	-0.175199
+2.573509	7.162977	0.734971	-3.145772	0.042900	0.549979	-0.172534
+2.574511	7.299437	0.751729	-3.155349	0.033308	0.556773	-0.171335
+2.575507	7.524477	0.988740	-3.368418	0.036905	0.552243	-0.173201
+2.576510	7.823732	1.134776	-3.641339	0.041968	0.549712	-0.175732
+2.577508	7.950617	1.072531	-3.705979	0.035040	0.557040	-0.190121
+2.578460	8.027226	1.127594	-3.409117	0.011991	0.570230	-0.215701
+2.579434	8.115806	1.129988	-3.078739	-0.020384	0.584219	-0.244479
+2.580436	8.336058	1.086896	-2.726815	-0.053825	0.601672	-0.269527
+2.581399	8.585038	0.952829	-2.595143	-0.087933	0.619659	-0.288046
+2.582377	8.877111	0.828339	-2.489805	-0.122706	0.639643	-0.305366
+2.583395	9.236218	0.679908	-2.386861	-0.158145	0.662026	-0.324152
+2.584401	9.583354	0.481203	-2.276735	-0.197315	0.683743	-0.341072
+2.585424	9.877821	0.217858	-2.169003	-0.234620	0.703727	-0.351997
+2.586480	10.141166	-0.057457	-1.922417	-0.266729	0.723179	-0.354262
+2.587476	10.361418	-0.380653	-1.963115	-0.295107	0.738501	-0.353196
+2.588483	10.564912	-0.600905	-1.874536	-0.322553	0.752090	-0.350531
+2.589481	10.684614	-0.830733	-1.864959	-0.353063	0.757686	-0.344936
+2.590482	10.900078	-1.094078	-1.738075	-0.386637	0.759951	-0.336809
+2.591443	11.096389	-1.228144	-1.613585	-0.421410	0.756753	-0.324152
+2.592477	11.151452	-1.331088	-1.565704	-0.457783	0.748760	-0.305766
+2.593482	11.228062	-1.443608	-1.577674	-0.494554	0.749692	-0.286447
+2.594483	11.417191	-1.563310	-1.575280	-0.526930	0.754089	-0.264331
+2.595483	11.328611	-1.862565	-1.544158	-0.552110	0.756487	-0.234087
+2.596409	11.127512	-1.994238	-1.546552	-0.572894	0.757020	-0.203577
+2.597425	10.902472	-2.018178	-1.604009	-0.592613	0.761150	-0.176931
+2.598425	10.785164	-2.039725	-1.623161	-0.612331	0.764614	-0.152150
+2.599425	10.476332	-2.123516	-1.584856	-0.630850	0.767545	-0.127236
+2.600425	10.313537	-2.082817	-1.711741	-0.645772	0.769277	-0.103254
+2.601426	10.272838	-1.989450	-1.831443	-0.652433	0.773807	-0.076741
+2.602396	10.196229	-1.941569	-1.953539	-0.651368	0.784332	-0.052360
+2.603508	9.947249	-1.934387	-2.082817	-0.640443	0.796590	-0.029311
+2.604512	9.762907	-1.891294	-2.303069	-0.622190	0.800054	-0.011858
+2.605451	9.631235	-1.936781	-2.585566	-0.592213	0.795124	-0.001199
+2.606511	9.470834	-1.955933	-2.736391	-0.548113	0.792992	0.005196
+2.607469	9.329585	-1.967903	-2.767514	-0.492556	0.796856	0.003864
+2.608511	8.886687	-1.785956	-2.750755	-0.438864	0.793525	-0.011325
+2.609511	8.738257	-1.627949	-2.978189	-0.389835	0.782467	-0.032109
+2.610510	8.575462	-1.369393	-3.179289	-0.343870	0.776338	-0.053026
+2.611433	8.661647	-1.094078	-3.284627	-0.295507	0.785531	-0.074476
+2.612514	8.577856	-0.730183	-3.255898	-0.247011	0.805516	-0.099524
+2.613456	8.513217	-0.450080	-3.219988	-0.206642	0.816041	-0.125237
+2.614426	8.482094	-0.114914	-3.253504	-0.172002	0.820305	-0.149885
+2.615420	8.482094	0.174765	-3.327720	-0.138560	0.824968	-0.168005
+2.616424	8.944145	0.512325	-3.466574	-0.099257	0.857077	-0.144156
+2.617406	10.897684	1.608797	-4.000446	-0.056890	0.922227	-0.057423
+2.618392	10.366206	2.061271	-4.740205	-0.016254	0.975519	-0.004130
+2.619405	8.280995	1.517823	-3.957353	0.011724	1.005496	-0.012657
+2.620486	7.668120	0.672726	-2.645417	0.025980	1.008560	-0.066349
+2.621442	7.636997	-0.050275	-2.125910	0.052093	1.012291	-0.101522
+2.622484	7.323377	-0.359106	-2.116334	0.092995	1.022150	-0.113247
+2.623488	7.361682	-0.337560	-2.659782	0.130833	1.018953	-0.123905
+2.624488	7.426321	-0.124490	-3.009312	0.159211	1.014156	-0.133631
+2.625492	7.732759	0.098156	-3.081133	0.180662	1.006296	-0.138694
+2.626487	8.041590	0.318408	-3.162531	0.196116	0.993106	-0.139360
+2.627488	8.261842	0.471626	-3.294203	0.211172	0.981781	-0.134164
+2.628488	8.407879	0.586541	-3.284627	0.229025	0.971522	-0.122972
+2.629432	8.376756	0.761306	-3.210412	0.247810	0.957133	-0.110848
+2.630404	8.357604	0.830733	-3.160137	0.264064	0.943544	-0.100057
+2.631403	8.290571	0.897766	-3.081133	0.279786	0.935417	-0.090198
+2.632407	8.118200	0.943253	-2.920732	0.293908	0.937149	-0.083936
+2.633406	7.986527	1.034227	-2.817789	0.306565	0.946608	-0.080738
+2.634417	7.921888	1.091684	-2.827365	0.316424	0.962063	-0.079539
+2.635501	7.847673	1.211386	-2.860881	0.322286	0.978450	-0.078873
+2.636501	7.720789	1.359816	-2.863275	0.325617	0.993505	-0.076075
+2.637504	7.490960	1.446002	-2.875246	0.330147	1.007495	-0.068214
+2.638500	7.273103	1.426850	-2.915944	0.334677	1.022683	-0.062352
+2.639448	7.105520	1.321512	-2.966219	0.340273	1.036939	-0.057689
+2.640504	6.921178	1.290389	-3.047617	0.345735	1.048796	-0.051161
+2.641430	6.672198	1.276025	-3.114650	0.349865	1.060521	-0.045165
+2.642500	6.406459	1.208992	-3.200835	0.353596	1.072511	-0.043433
+2.643502	6.243664	1.189839	-3.203229	0.355594	1.085168	-0.042234
+2.644501	6.092839	1.175475	-3.145772	0.358259	1.096893	-0.039969
+2.645507	5.915680	1.175475	-3.219988	0.363455	1.111548	-0.038104
+2.646447	5.822312	1.261661	-3.145772	0.368251	1.128868	-0.035839
+2.647421	5.702610	1.223356	-3.133802	0.373447	1.152317	-0.032508
+2.648411	5.590090	1.309542	-3.181683	0.377711	1.176698	-0.030243
+2.649438	5.527845	1.314330	-3.124226	0.380775	1.198548	-0.026247
+2.650435	5.580514	1.340664	-3.193653	0.386904	1.219599	-0.021583
+2.651409	5.618819	1.376575	-3.155349	0.392366	1.238384	-0.014389
+2.652416	5.829495	1.498671	-3.035646	0.396230	1.258636	-0.008260
+2.653437	6.095233	1.517823	-3.026070	0.401825	1.280086	-0.004263
+2.654511	6.236482	1.592039	-2.956643	0.405556	1.299404	0.000533
+2.655510	6.653045	1.572886	-2.858487	0.408221	1.313926	0.001998
+2.656509	6.985817	1.580068	-2.674146	0.409286	1.322320	0.001332
+2.657509	7.376046	1.572886	-2.616689	0.409819	1.333245	-0.001466
+2.658508	7.680090	1.546552	-2.487411	0.411152	1.344570	-0.005329
+2.659512	7.974557	1.410091	-2.212096	0.409553	1.354695	-0.015855
+2.660468	8.400697	1.335876	-2.113940	0.405689	1.362423	-0.032242
+2.661480	8.668830	1.285601	-1.982268	0.398495	1.371616	-0.053026
+2.662509	8.944145	1.149141	-1.797926	0.390501	1.377211	-0.075942
+2.663452	9.164396	1.031833	-1.694982	0.380109	1.374680	-0.099391
+2.664431	9.320009	0.900160	-1.656678	0.368651	1.370683	-0.122706
+2.665404	9.475622	0.761306	-1.544158	0.360124	1.366420	-0.147221
+2.666404	9.585748	0.593723	-1.556128	0.353862	1.363355	-0.172002
+2.667404	9.712632	0.490779	-1.501065	0.348400	1.361757	-0.194384
+2.668404	9.837123	0.406987	-1.407697	0.341338	1.358026	-0.214502
+2.669450	9.940066	0.373471	-1.383757	0.334943	1.349499	-0.230357
+2.670449	10.086103	0.402199	-1.340664	0.331080	1.342571	-0.239816
+2.671414	10.102861	0.342348	-1.127594	0.328149	1.342305	-0.247943
+2.672449	10.270444	0.361500	-1.086896	0.322020	1.341639	-0.255804
+2.673451	10.445209	0.363895	-0.976770	0.314692	1.336176	-0.260067
+2.674448	10.665461	0.404593	-0.840309	0.306032	1.331247	-0.261933
+2.675450	10.828256	0.466838	-0.699061	0.298704	1.332712	-0.263265
+2.676450	11.060479	0.574570	-0.600905	0.288579	1.337109	-0.266862
+2.677450	11.254396	0.627239	-0.553024	0.277920	1.338175	-0.270593
+2.678450	11.467466	0.672726	-0.459656	0.266862	1.334444	-0.271259
+2.679447	11.680536	0.718213	-0.380653	0.254205	1.328182	-0.271126
+2.680390	11.931910	0.660756	-0.306437	0.242747	1.324052	-0.271126
+2.681437	12.061188	0.648786	-0.213070	0.235153	1.326717	-0.271259
+2.682441	12.214407	0.569782	-0.122096	0.228625	1.328449	-0.275123
+2.683413	12.267076	0.548236	-0.112520	0.222230	1.323919	-0.281118
+2.684413	12.353262	0.531478	-0.162795	0.211038	1.315259	-0.291110
+2.685439	12.408325	0.488385	-0.105338	0.201179	1.311662	-0.301769
+2.686438	12.525633	0.423746	0.033517	0.193851	1.315525	-0.314559
+2.687509	12.516057	0.363895	0.023940	0.189988	1.320455	-0.326949
+2.688509	12.415507	0.342348	0.126884	0.183459	1.326583	-0.337874
+2.689510	12.408325	0.263345	0.234616	0.173734	1.327116	-0.352263
+2.690508	12.343686	0.222646	0.239404	0.161077	1.327250	-0.371848
+2.691444	12.269470	0.213070	0.260951	0.147221	1.330847	-0.391300
+2.692508	12.125828	0.210676	0.239404	0.132165	1.332446	-0.407688
+2.693464	11.963033	0.237010	0.263345	0.118043	1.334711	-0.423942
+2.694507	11.812208	0.318408	0.342348	0.102721	1.338708	-0.439663
+2.695507	11.647019	0.282497	0.411775	0.084868	1.344969	-0.455251
+2.696457	11.551257	0.342348	0.500355	0.065816	1.352430	-0.472038
+2.697410	11.457890	0.390229	0.502749	0.045299	1.360824	-0.484162
+2.698404	11.338187	0.418958	0.567388	0.024115	1.370550	-0.495487
+2.699384	11.230456	0.490779	0.505143	0.005862	1.382674	-0.507345
+2.700404	11.077237	0.555418	0.454868	-0.009593	1.397462	-0.518270
+2.701380	11.029356	0.533872	0.428534	-0.023848	1.409187	-0.527329
+2.702374	10.921624	0.620057	0.390229	-0.038237	1.419446	-0.534923
+2.703455	10.897684	0.603299	0.414169	-0.053159	1.431303	-0.544649
+2.704428	10.919230	0.615269	0.466838	-0.065683	1.446358	-0.554375
+2.705467	10.938382	0.624845	0.402199	-0.072078	1.457550	-0.562902
+2.706401	10.909654	0.545842	0.433322	-0.077274	1.467809	-0.567299
+2.707392	10.847409	0.452474	0.490779	-0.079139	1.478867	-0.573294
+2.708439	10.785164	0.375865	0.426140	-0.078074	1.490991	-0.581421
+2.709467	10.689402	0.268133	0.481203	-0.075809	1.506179	-0.592746
+2.710462	10.658279	0.174765	0.620057	-0.069946	1.518969	-0.605936
+2.711465	10.615187	0.122096	0.643998	-0.063018	1.530028	-0.623256
+2.712468	10.476332	-0.023940	0.684696	-0.048629	1.546681	-0.636712
+2.713401	10.282415	-0.155613	0.821157	-0.024648	1.567865	-0.642441
+2.714389	10.057375	-0.292073	0.773276	0.003597	1.583853	-0.646838
+2.715389	9.863457	-0.371077	0.756518	0.033708	1.589982	-0.655098
+2.716389	9.679116	-0.390229	0.804398	0.061953	1.592380	-0.664957
+2.717440	9.636023	-0.430928	0.813975	0.086734	1.596377	-0.674017
+2.718450	9.511533	-0.445292	0.744547	0.109649	1.604371	-0.677881
+2.719508	9.310433	-0.421352	0.555418	0.130966	1.613830	-0.681078
+2.720508	9.071029	-0.397411	0.469232	0.153349	1.627420	-0.683876
+2.721509	8.896264	-0.361500	0.466838	0.172801	1.642874	-0.681078
+2.722507	8.702346	-0.347136	0.366289	0.190654	1.653000	-0.669753
+2.723508	8.541945	-0.272921	0.165189	0.208374	1.656064	-0.657096
+2.724461	8.345634	-0.193917	0.205888	0.228758	1.661394	-0.640176
+2.725485	8.247478	-0.213070	0.169977	0.253672	1.669521	-0.620724
+2.726448	8.008074	-0.198706	0.043093	0.279519	1.674717	-0.600074
+2.727510	7.737547	-0.198706	-0.148431	0.300170	1.680712	-0.577158
+2.728446	7.469414	-0.124490	-0.304043	0.319489	1.690172	-0.557706
+2.729471	7.263526	0.026334	-0.351924	0.337475	1.707758	-0.538787
+2.730449	7.074397	0.165189	-0.423746	0.353329	1.729741	-0.513207
+2.731436	6.839781	0.332772	-0.703849	0.365320	1.755721	-0.489092
+2.732436	6.535737	0.490779	-0.979164	0.373980	1.781835	-0.463911
+2.733424	6.076081	0.627239	-1.268843	0.377577	1.809014	-0.433002
+2.734435	5.578120	0.744547	-1.407697	0.379309	1.838458	-0.395564
+2.735436	5.235772	0.804398	-1.687800	0.383972	1.875096	-0.354928
+2.736435	4.986792	0.866644	-1.831443	0.383173	1.899478	-0.316691
+2.737439	4.630079	0.914524	-1.987056	0.380375	1.910936	-0.276188
+2.738509	4.285337	0.919312	-2.106758	0.381974	1.917064	-0.231423
+2.739509	3.947777	0.948041	-2.178579	0.387570	1.919196	-0.181461
+2.740514	3.725131	0.950435	-2.176185	0.393032	1.916398	-0.128701
+2.741509	3.370812	0.924101	-2.058877	0.397695	1.915332	-0.074476
+2.742511	3.174501	0.960011	-2.013390	0.403824	1.913201	-0.019985
+2.743452	3.064375	1.048591	-1.852989	0.407954	1.908404	0.034773
+2.744505	2.999736	1.091684	-1.766804	0.408087	1.902409	0.083003
+2.745509	3.033252	1.098866	-1.819473	0.401559	1.889619	0.127636
+2.746507	3.160137	1.163505	-1.675830	0.399560	1.889752	0.167605
+2.747450	3.392359	1.206598	-1.575280	0.399294	1.892017	0.201579
+2.748436	3.715555	1.331088	-1.376575	0.397162	1.895214	0.229424
+2.749405	4.045933	1.434032	-1.297571	0.393698	1.900410	0.255404
+2.750405	4.122542	1.546552	-1.223356	0.393432	1.907205	0.285781
+2.751398	4.400251	1.611191	-1.012680	0.396896	1.907472	0.313493
+2.752404	4.800056	1.726105	-0.840309	0.403158	1.906672	0.335343
+2.753443	5.278865	1.876930	-0.531478	0.409686	1.910003	0.350265
+2.754413	5.884558	2.085211	-0.450080	0.420078	1.910536	0.362922
+2.755445	6.396883	2.336586	-0.141249	0.433268	1.909737	0.375179
+2.756398	6.834993	2.666964	0.081397	0.449256	1.916132	0.386504
+2.757405	7.517295	2.956643	0.395017	0.462446	1.923593	0.390368
+2.758448	8.139746	3.265475	0.878614	0.469507	1.927723	0.388636
+2.759448	8.769379	3.476150	1.170687	0.472838	1.931720	0.384239
+2.760449	9.422953	3.641339	1.455578	0.478034	1.941446	0.376245
+2.761429	10.007100	3.794558	1.759622	0.484562	1.955568	0.359991
+2.762401	10.517031	3.854409	2.130698	0.488026	1.967825	0.338807
+2.763361	11.048508	3.823287	2.549656	0.487493	1.976885	0.307364
+2.764354	11.694900	3.701190	2.769908	0.484029	1.989942	0.263665
+2.765416	12.240742	3.612611	3.071557	0.481897	2.003665	0.207974
+2.766413	12.712368	3.478544	3.380389	0.482430	2.015522	0.145888
+2.767518	13.078657	3.265475	3.653310	0.481364	2.023250	0.084735
+2.768508	13.365942	3.040435	3.911866	0.480832	2.028179	0.023848
+2.769512	13.677167	2.870458	4.089025	0.472305	2.023649	-0.038104
+2.770513	13.672379	2.650206	4.282943	0.463645	2.020452	-0.100856
+2.771510	13.827992	2.444318	4.464890	0.455917	2.013657	-0.170536
+2.772508	13.909390	2.190549	4.412221	0.436732	2.001400	-0.243147
+2.773519	14.065002	2.042119	4.620503	0.404623	1.988343	-0.316025
+2.774463	14.232585	1.912840	4.685142	0.369583	1.979283	-0.387570
+2.775505	14.203857	1.793138	4.756963	0.343470	1.970757	-0.454052
+2.776508	14.129642	1.601615	4.704294	0.311095	1.973155	-0.515472
+2.777512	14.069791	1.460366	4.292519	0.281251	1.979683	-0.574360
+2.778509	13.854327	1.345452	4.668384	0.259534	1.975420	-0.625121
+2.779507	13.665197	1.125200	4.752175	0.227026	1.975953	-0.669087
+2.780446	13.569436	1.019862	4.256608	0.165207	1.998469	-0.704127
+2.781415	13.346790	1.031833	3.732313	0.108717	2.019253	-0.740499
+2.782413	13.054716	1.089290	4.428979	0.087133	2.005930	-0.777271
+2.783395	12.738703	0.873826	5.171133	0.097658	1.959832	-0.806715
+2.784410	12.386778	0.636815	6.047353	0.130167	1.888286	-0.829498
+2.785415	11.936698	0.406987	6.040170	0.146821	1.828998	-0.848816
+2.786413	11.400433	0.294467	5.228590	0.150285	1.792760	-0.863072
+2.787412	11.065267	0.323196	4.934123	0.159345	1.752657	-0.870666
+2.788442	10.794740	0.287285	5.235772	0.174400	1.696433	-0.873997
+2.789509	10.442815	0.316014	5.286047	0.187323	1.638478	-0.876262
+2.790508	10.169895	0.347136	5.111282	0.191320	1.595977	-0.874263
+2.791507	9.911338	0.418958	4.852725	0.184392	1.571596	-0.873064
+2.792463	9.664751	0.509931	4.519953	0.176798	1.560671	-0.869467
+2.793507	9.367890	0.651180	4.206333	0.171202	1.555608	-0.865204
+2.794508	9.217065	0.792428	3.921442	0.162142	1.562136	-0.852014
+2.795509	9.063847	1.015074	3.358842	0.147087	1.579723	-0.836026
+2.796455	8.786138	1.208992	3.152955	0.140559	1.589449	-0.817640
+2.797410	8.510823	1.129988	3.686826	0.151884	1.577058	-0.802718
+2.798402	8.242690	1.019862	3.852015	0.166273	1.552943	-0.785531
+2.799396	7.941041	1.165899	3.646127	0.180129	1.532959	-0.761816
+2.800401	7.759093	1.345452	3.543184	0.183193	1.520835	-0.743963
+2.801400	7.804580	1.594433	3.437846	0.174000	1.530161	-0.745562
+2.802452	7.457444	1.630343	3.351660	0.156413	1.558806	-0.723312
+2.803420	6.957089	1.726105	2.966219	0.139493	1.590381	-0.683609
+2.804446	6.916390	1.848201	2.030148	0.112980	1.622224	-0.650701
+2.805451	6.854145	1.970297	1.946357	0.086467	1.670453	-0.626986
+2.806446	6.679380	1.987056	2.580778	0.085002	1.706426	-0.613263
+2.807451	6.497433	1.960721	3.222382	0.106319	1.713487	-0.605536
+2.808449	6.313091	1.908052	2.978189	0.121240	1.720415	-0.602338
+2.809448	6.155084	1.896082	2.736391	0.137095	1.747461	-0.592613
+2.810452	5.829495	1.872142	2.678934	0.160277	1.768112	-0.568098
+2.811449	5.807948	1.838625	2.207308	0.187590	1.773574	-0.548646
+2.812428	5.757673	1.888900	1.812291	0.218899	1.786098	-0.534391
+2.813397	5.554180	1.972691	2.099576	0.260600	1.798888	-0.522400
+2.814373	5.393779	1.972691	2.161821	0.300570	1.811945	-0.510675
+2.815369	5.235772	2.109152	1.795532	0.333478	1.831263	-0.502415
+2.816448	5.056219	2.288705	1.465154	0.363188	1.860841	-0.494421
+2.817454	4.888636	2.410801	1.192233	0.386637	1.896680	-0.485361
+2.818450	4.675566	2.650206	1.053379	0.407421	1.939181	-0.479366
+2.819451	4.536711	2.853699	0.864250	0.421011	1.990874	-0.475369
+2.820448	4.555864	2.982978	0.653574	0.427539	2.056025	-0.469507
+2.821453	4.539105	3.248716	0.459656	0.420611	2.137296	-0.469107
+2.822449	4.417009	3.478544	0.474021	0.411818	2.221498	-0.471372
+2.823431	4.220698	3.564730	0.462050	0.409153	2.301037	-0.471772
+2.824468	3.892714	3.617399	0.521901	0.407288	2.381109	-0.469640
+2.825409	3.677250	3.698796	0.897766	0.407421	2.454253	-0.470706
+2.826444	3.466574	3.708373	0.761306	0.387836	2.539521	-0.471772
+2.827449	3.428270	3.682038	0.495567	0.342538	2.652234	-0.475636
+2.828445	3.241534	3.698796	0.888190	0.318556	2.772675	-0.488292
+2.829409	2.920732	3.588670	1.003104	0.333211	2.866737	-0.505613
+2.830369	2.604719	3.521637	0.574570	0.347867	2.932020	-0.506012
+2.831370	2.384467	3.559942	0.691878	0.342538	2.983980	-0.497086
+2.832441	2.279129	3.686826	1.173081	0.322953	3.046865	-0.492956
+2.833416	2.465864	3.622187	1.034227	0.303368	3.134531	-0.498018
+2.834429	2.432348	3.682038	0.215464	0.297905	3.227127	-0.505080
+2.835451	2.152245	3.784982	0.553024	0.318822	3.272426	-0.497885
+2.836447	1.977479	3.756253	0.474021	0.333744	3.295874	-0.469507
+2.837449	1.953539	3.935807	0.730183	0.345735	3.335311	-0.440862
+2.838447	2.111546	3.916654	0.466838	0.352930	3.394865	-0.421410
+2.839449	2.238430	4.144088	0.402199	0.369583	3.443894	-0.407421
+2.840432	2.279129	4.282943	0.897766	0.387436	3.472939	-0.390101
+2.841450	2.652600	4.378705	0.971981	0.394631	3.515173	-0.370516
+2.842448	3.219988	4.548682	1.429244	0.412484	3.560072	-0.355861
+2.843448	3.459392	4.747387	2.324616	0.428871	3.595645	-0.335077
+2.844431	3.981293	4.859907	2.585566	0.431003	3.633749	-0.309896
+2.845461	4.663596	5.209437	2.518533	0.426473	3.681446	-0.285248
+2.846389	4.843149	5.467994	2.836941	0.416348	3.719283	-0.257403
+2.847375	5.173527	5.702610	3.306173	0.403025	3.730342	-0.234753
+2.848361	5.812736	6.009048	4.048327	0.392899	3.725545	-0.226760
+2.849438	6.624317	6.004260	4.476860	0.381974	3.726078	-0.223029
+2.850443	7.553206	6.140720	5.132828	0.359458	3.725279	-0.216234
+2.851508	8.252266	6.088051	5.305199	0.304567	3.729009	-0.203178
+2.852508	8.745439	6.167055	5.810342	0.249409	3.740600	-0.189455
+2.853508	9.358314	6.095233	5.915680	0.224495	3.743265	-0.191720
+2.854440	10.028646	5.901316	6.978635	0.231822	3.719417	-0.206242
+2.855510	10.500272	5.645153	8.290571	0.234221	3.669055	-0.228092
+2.856510	10.969505	5.266895	8.908234	0.219165	3.619893	-0.255804
+2.857513	11.697294	5.017914	9.439711	0.193718	3.577392	-0.286847
+2.858508	12.235954	4.711477	9.947249	0.163208	3.533293	-0.315492
+2.859509	12.549573	4.282943	10.366206	0.155881	3.469075	-0.345602
+2.860509	12.908680	3.811316	10.847409	0.163608	3.384740	-0.373847
+2.861511	13.365942	3.445028	11.568016	0.179596	3.270294	-0.400760
+2.862463	13.516767	3.018888	12.235954	0.186657	3.149187	-0.430204
+2.863450	13.672379	2.595143	12.391566	0.201179	3.029279	-0.475369
+2.864438	13.950088	2.219278	12.757855	0.207708	2.909637	-0.522000
+2.865436	14.081761	1.742863	12.760249	0.209573	2.788130	-0.566233
+2.866434	14.251738	1.285601	13.861509	0.223828	2.643974	-0.607401
+2.867439	14.263708	0.845097	14.225403	0.231423	2.500617	-0.640842
+2.868440	14.045850	0.620057	13.279756	0.210372	2.392300	-0.671352
+2.869436	14.096125	0.464444	12.803342	0.175332	2.307832	-0.703061
+2.870435	13.985999	0.205888	13.401853	0.164141	2.199781	-0.741565
+2.871511	13.713078	-0.138854	13.698714	0.155747	2.070946	-0.779003
+2.872509	13.593376	-0.416563	13.416217	0.136162	1.948107	-0.805916
+2.873443	13.442551	-0.536266	13.049928	0.118176	1.849250	-0.822969
+2.874506	13.176812	-0.596117	12.798554	0.103654	1.749193	-0.837625
+2.875511	12.879951	-0.761306	12.678852	0.099124	1.643674	-0.848949
+2.876509	12.437053	-0.842703	12.190467	0.093928	1.548680	-0.850548
+2.877512	11.843331	-0.746941	11.366916	0.077407	1.462746	-0.847617
+2.878510	11.287913	-0.538660	10.957535	0.051694	1.388136	-0.837492
+2.879507	10.639127	-0.349530	10.495484	0.011858	1.319123	-0.818173
+2.880462	10.193835	-0.019152	9.985553	-0.033708	1.263032	-0.798055
+2.881402	9.741361	0.253769	9.851487	-0.075542	1.218533	-0.780335
+2.882403	9.207489	0.435716	9.664751	-0.113380	1.204277	-0.758086
+2.883394	8.683194	0.569782	9.403801	-0.158945	1.208008	-0.737701
+2.884404	8.144534	0.804398	8.956115	-0.214636	1.235853	-0.719848
+2.885399	7.579540	0.988740	8.434213	-0.284049	1.275423	-0.705193
+2.886449	6.887662	1.118018	8.039196	-0.345868	1.318456	-0.681744
+2.887442	6.404065	1.208992	7.854855	-0.397296	1.369484	-0.655897
+2.888448	6.054535	1.273631	8.096653	-0.426606	1.408254	-0.634847
+2.889450	5.786402	1.204204	8.450972	-0.437531	1.449156	-0.615262
+2.890449	5.420113	1.031833	8.352816	-0.434201	1.502848	-0.587816
+2.891449	5.106494	0.928889	7.809368	-0.421943	1.570263	-0.549312
+2.892432	4.819208	0.888190	7.902736	-0.390900	1.623156	-0.506812
+2.893376	4.426585	0.823551	8.276207	-0.343337	1.648337	-0.465243
+2.894372	4.187181	0.854673	7.833309	-0.305233	1.677115	-0.421544
+2.895356	4.077055	1.043803	7.086367	-0.276988	1.720015	-0.375712
+2.896370	3.986082	1.340664	6.779930	-0.253539	1.764781	-0.328149
+2.897419	3.976505	1.649496	6.578830	-0.233554	1.795824	-0.280985
+2.898417	4.014810	1.939175	6.088051	-0.217567	1.828199	-0.235953
+2.899419	4.091419	2.214490	5.575726	-0.214502	1.876296	-0.194251
+2.900413	4.242244	2.552050	5.434478	-0.208773	1.926391	-0.154815
+2.901418	4.510377	2.860881	5.527845	-0.193851	1.973288	-0.124172
+2.902418	4.503195	3.064375	5.372232	-0.171202	2.000734	-0.110182
+2.903419	4.553470	3.169713	5.506299	-0.153216	2.014856	-0.098724
+2.904417	4.606139	3.145772	5.602061	-0.154948	2.047631	-0.080472
+2.905418	4.572622	3.239140	5.168739	-0.172401	2.107585	-0.063285
+2.906416	4.515165	3.349266	4.938911	-0.194917	2.164741	-0.051694
+2.907416	4.361946	3.466574	5.295623	-0.226227	2.195917	-0.039703
+2.908413	4.086631	3.409117	5.245348	-0.251674	2.213904	-0.029977
+2.909372	3.784982	3.394753	5.140010	-0.259934	2.244014	-0.021583
+2.910363	3.641339	3.320538	4.974821	-0.282317	2.293842	-0.018652
+2.911370	3.607823	3.354054	4.780904	-0.323885	2.357793	-0.025047
+2.912364	3.358842	3.346872	5.010732	-0.346135	2.403092	-0.037838
+2.913367	2.927915	3.236746	5.132828	-0.367851	2.434801	-0.051427
+2.914366	2.846517	3.124226	5.092129	-0.402225	2.463845	-0.063418
+2.915361	2.698086	2.975795	4.891030	-0.413949	2.486228	-0.071279
+2.916370	2.659782	2.906368	5.037066	-0.377178	2.486095	-0.073810
+2.917370	2.571202	2.753149	5.223802	-0.334410	2.463979	-0.078606
+2.918370	2.461076	2.638235	4.436162	-0.318023	2.457983	-0.091397
+2.919369	2.362920	2.731603	4.156059	-0.315625	2.458783	-0.110049
+2.920391	2.315040	2.712451	3.966929	-0.317890	2.457983	-0.123639
+2.921365	2.169003	2.760332	3.993264	-0.334144	2.466243	-0.130167
+2.922361	2.044513	2.765120	4.048327	-0.347334	2.477968	-0.135763
+2.923370	1.821867	2.765120	3.804134	-0.357459	2.490625	-0.143357
+2.924370	1.472336	2.777090	3.547972	-0.360923	2.502482	-0.153749
+2.925369	1.177869	2.722027	3.536001	-0.347067	2.505813	-0.170136
+2.926370	1.153929	2.635841	3.521637	-0.343204	2.513541	-0.182793
+2.927365	1.137170	2.451500	3.988476	-0.357726	2.528995	-0.184126
+2.928366	1.079713	2.451500	3.751465	-0.367851	2.557907	-0.181461
+2.929370	0.979164	2.461076	3.306173	-0.368917	2.599608	-0.186257
+2.930370	0.842703	2.463470	2.760332	-0.383972	2.664492	-0.192519
+2.931369	0.737365	2.580778	2.420377	-0.413550	2.743498	-0.191054
+2.932372	0.416563	2.587960	3.124226	-0.399427	2.789196	-0.191187
+2.933344	-0.062245	2.458682	3.825681	-0.346401	2.793459	-0.188389
+2.934365	-0.059851	2.286311	3.425875	-0.301769	2.797590	-0.181861
+2.935378	-0.146037	2.432348	2.786666	-0.262466	2.817441	-0.178263
+2.936370	-0.248980	2.609507	2.485017	-0.239150	2.862207	-0.176531
+2.937370	-0.392623	2.827365	2.765120	-0.222230	2.914433	-0.182926
+2.938370	-0.603299	3.042829	2.592749	-0.204377	2.973455	-0.196516
+2.939370	-0.478809	3.375601	2.781878	-0.220098	3.052994	-0.205842
+2.940350	-0.232222	3.646127	2.932703	-0.241681	3.160911	-0.210905
+2.941370	0.067033	4.069873	3.346872	-0.249809	3.235254	-0.208374
+2.942370	-0.126884	4.309277	3.868773	-0.250075	3.261634	-0.205709
+2.943370	-0.220252	4.546288	3.691614	-0.251407	3.270960	-0.201712
+2.944370	-0.119702	4.713871	4.175211	-0.248876	3.253107	-0.191453
+2.945369	0.055063	4.941305	4.417009	-0.226360	3.215802	-0.172801
+2.946373	0.308832	4.948487	4.184787	-0.207574	3.195818	-0.155481
+2.947370	0.811581	4.783298	4.756963	-0.233421	3.197150	-0.125637
+2.948370	0.969587	4.962851	5.985107	-0.259668	3.189822	-0.095926
+2.949385	1.199416	4.929334	6.408853	-0.275256	3.181962	-0.075142
+2.950369	1.489095	5.080159	6.356184	-0.261933	3.180763	-0.064617
+2.951370	1.884112	5.149586	6.928360	-0.263931	3.189423	-0.049429
+2.952370	2.073241	4.955669	7.821338	-0.291910	3.201280	-0.038770
+2.953371	2.334192	4.835967	8.005680	-0.328415	3.216469	-0.032242
+2.954370	2.935097	4.665990	8.841201	-0.371449	3.220466	-0.009060
+2.955370	3.114650	4.637261	9.659963	-0.369583	3.197550	0.007461
+2.956370	3.524031	4.522347	10.809104	-0.358925	3.147721	0.019185
+2.957370	4.134512	4.500801	11.120330	-0.363855	3.092963	0.031709
+2.958370	4.608533	4.304489	11.182575	-0.383839	3.047132	0.038770
+2.959370	4.912576	4.211122	10.878531	-0.379309	3.004098	0.029044
+2.960369	5.453630	4.031568	11.350158	-0.330547	2.949873	0.013723
+2.961370	5.951591	3.717949	12.302987	-0.289245	2.882325	0.003198
+2.962370	6.274787	3.567124	13.648439	-0.281118	2.806383	0.001332
+2.963371	6.645863	3.306173	14.069791	-0.286447	2.737902	-0.001732
+2.964384	6.617135	3.054799	14.079367	-0.263665	2.682078	-0.018119
+2.965463	6.732049	2.731603	14.357076	-0.249142	2.634115	-0.047430
+2.966449	6.823022	2.669358	15.108805	-0.266329	2.583620	-0.076075
+2.967449	7.119884	2.492199	16.231611	-0.261933	2.499951	-0.101655
+2.968447	7.277891	2.214490	16.660145	-0.231556	2.403092	-0.124571
+2.969445	7.452656	1.891294	16.004177	-0.205975	2.321155	-0.154149
+2.970448	7.687272	1.721317	16.159790	-0.185458	2.252274	-0.186124
+2.971401	7.723183	1.544158	16.540443	-0.156413	2.179930	-0.225694
+2.972383	7.759093	1.218568	16.523685	-0.112847	2.108518	-0.275522
+2.973403	7.821338	0.895372	17.004887	-0.085934	2.040303	-0.322153
+2.974386	7.926676	0.706243	17.723100	-0.112314	1.981149	-0.336809
+2.975467	7.787822	0.359106	17.533971	-0.142424	1.923859	-0.334277
+2.976405	7.546023	-0.004788	17.074314	-0.127236	1.852980	-0.334011
+2.977405	7.330560	-0.253769	16.676903	-0.077541	1.766646	-0.352796
+2.978397	7.354500	-0.282497	16.289068	-0.032775	1.673118	-0.383306
+2.979399	7.423927	-0.275315	15.898839	0.001732	1.579190	-0.411951
+2.980361	7.218040	-0.229828	15.379332	0.023982	1.500051	-0.433268
+2.981401	6.897238	-0.318408	15.202173	0.036905	1.436499	-0.446058
+2.982398	6.530949	-0.450080	15.171050	0.036372	1.379476	-0.451787
+2.983401	6.274787	-0.596117	14.737729	0.026113	1.332312	-0.450855
+2.984396	5.915680	-0.711031	14.038668	0.010392	1.299804	-0.446325
+2.985429	5.537421	-0.754124	13.521555	-0.011058	1.275956	-0.443394
+2.986451	5.242954	-0.766094	13.286938	-0.037704	1.254905	-0.443394
+2.987500	4.991580	-0.787640	12.896709	-0.065017	1.233855	-0.444326
+2.988497	4.491225	-0.916918	12.384384	-0.092729	1.220265	-0.442194
+2.989505	4.091419	-0.950435	12.159344	-0.121907	1.213070	-0.440462
+2.990444	3.638945	-0.928889	11.862483	-0.146821	1.208274	-0.438864
+2.991461	3.131408	-1.007892	11.706870	-0.168671	1.206809	-0.434467
+2.992497	2.681328	-1.034227	11.527317	-0.189322	1.205210	-0.430470
+2.993425	2.327010	-1.053379	11.232850	-0.208507	1.200147	-0.429804
+2.994468	2.068453	-1.070137	10.809104	-0.226760	1.198681	-0.431669
+2.995486	1.829049	-1.046197	10.497878	-0.246211	1.202279	-0.435133
+2.996429	1.589645	-0.926495	10.165106	-0.268194	1.206276	-0.432735
+2.997417	1.347846	-0.849885	9.794030	-0.295773	1.206942	-0.430337
+2.998414	1.139564	-0.675120	9.494774	-0.321620	1.204144	-0.425141
+2.999413	1.010286	-0.564994	9.267340	-0.341605	1.200547	-0.417813
+3.000415	0.945647	-0.500355	9.138062	-0.362522	1.193485	-0.408487
+3.001409	0.804398	-0.433322	8.944145	-0.387969	1.186691	-0.402092
+3.002409	0.830733	-0.287285	8.661647	-0.418213	1.184292	-0.396896
+3.003438	0.828339	-0.105338	8.369574	-0.453119	1.186557	-0.391167
+3.004399	0.809187	0.143643	8.333664	-0.489358	1.189222	-0.382773
+3.005441	0.754124	0.304043	8.345634	-0.519868	1.189089	-0.372381
+3.006414	0.682302	0.428534	8.400697	-0.546914	1.186424	-0.361856
+3.007417	0.610481	0.428534	8.276207	-0.572628	1.183227	-0.348799
+3.008509	0.636815	0.505143	8.091865	-0.597942	1.182028	-0.336009
+3.009509	0.665544	0.576964	7.881189	-0.624322	1.184559	-0.323086
+3.010509	0.682302	0.701455	7.735153	-0.650835	1.189888	-0.306565
+3.011459	0.634421	0.778064	7.833309	-0.672685	1.194152	-0.290311
+3.012417	0.564994	0.787640	7.816550	-0.694135	1.198149	-0.276855
+3.013421	0.442898	0.866644	7.694454	-0.715185	1.204943	-0.264198
+3.014416	0.368683	0.897766	7.749517	-0.733305	1.213337	-0.253139
+3.015423	0.256163	0.859461	7.672908	-0.746228	1.222130	-0.243547
+3.016434	0.102944	0.883402	7.620239	-0.755155	1.235187	-0.235819
+3.017392	0.033517	0.907342	7.601086	-0.763681	1.250375	-0.228758
+3.018395	-0.023940	0.926495	7.610663	-0.768078	1.267429	-0.224495
+3.019439	-0.069427	0.998316	7.483778	-0.770476	1.285815	-0.220764
+3.020470	-0.083792	1.050985	7.536447	-0.773274	1.305133	-0.217700
+3.021475	-0.189129	1.156323	7.404775	-0.777937	1.327783	-0.216767
+3.022474	-0.402199	1.311936	7.275497	-0.781401	1.350698	-0.212504
+3.023433	-0.655968	1.388545	7.309013	-0.771675	1.357626	-0.202112
+3.024461	-0.967193	1.366999	7.251556	-0.754888	1.349899	-0.183726
+3.025479	-1.091684	1.383757	6.887662	-0.746495	1.344969	-0.165074
+3.026475	-1.242508	1.405303	6.669804	-0.748493	1.352031	-0.144822
+3.027475	-1.441214	1.556128	6.700926	-0.761417	1.368418	-0.131100
+3.028469	-1.446002	1.661466	6.741625	-0.784332	1.392533	-0.120308
+3.029409	-1.316724	1.807502	6.645863	-0.811778	1.428639	-0.112181
+3.030400	-1.225750	2.010996	6.408853	-0.846018	1.473138	-0.106319
+3.031396	-1.192233	2.228854	6.471098	-0.874930	1.516571	-0.102322
+3.032397	-1.134776	2.429954	6.550102	-0.897179	1.555075	-0.100190
+3.033397	-1.144353	2.602325	6.466310	-0.911302	1.587717	-0.093795
+3.034412	-1.086896	2.669358	6.487856	-0.909037	1.609700	-0.084069
+3.035490	-1.086896	2.784272	6.887662	-0.893715	1.616628	-0.074210
+3.036501	-0.993528	2.820183	7.244374	-0.884522	1.615296	-0.068747
+3.037504	-0.914524	2.877640	7.476596	-0.870799	1.615695	-0.065417
+3.038501	-0.988740	3.023676	7.385623	-0.833495	1.617827	-0.061286
+3.039501	-1.010286	3.129014	7.095943	-0.771009	1.606369	-0.062352
+3.040468	-1.364604	3.088315	6.676986	-0.682544	1.580389	-0.065417
+3.041500	-1.539370	2.865669	6.863721	-0.636179	1.572528	-0.054891
+3.042461	-1.352634	2.554444	8.843595	-0.732239	1.591047	-0.002132
+3.043460	-2.030148	2.757937	8.810078	-0.832296	1.621957	0.055424
+3.044437	-2.200125	2.901580	7.735153	-0.844153	1.641409	0.079406
+3.045428	-1.642313	2.865669	7.531659	-0.802319	1.627819	0.069680
+3.046447	-1.017468	3.282233	8.106229	-0.757420	1.595444	0.047963
+3.047418	-0.232222	3.610217	8.838807	-0.761283	1.574127	0.037971
+3.048415	0.234616	3.820893	9.382254	-0.793259	1.559472	0.033841
+3.049437	0.675120	4.285337	9.209883	-0.809380	1.534025	0.025447
+3.050436	1.055773	4.505589	9.281705	-0.800054	1.504314	0.020651
+3.051434	1.249690	4.699506	9.695874	-0.781934	1.470606	0.022649
+3.052434	1.352634	4.723447	10.050192	-0.760217	1.429571	0.029044
+3.053376	1.434032	4.725841	10.473938	-0.735703	1.384539	0.037172
+3.054369	1.857777	4.730629	10.732495	-0.717717	1.336043	0.042368
+3.055468	2.255188	4.843149	10.854591	-0.702928	1.295940	0.045832
+3.056448	2.403619	4.914970	11.151452	-0.689605	1.268495	0.050495
+3.057450	2.638235	4.931729	11.637443	-0.667489	1.235587	0.062352
+3.058448	2.844123	4.835967	12.209619	-0.633515	1.189755	0.073677
+3.059449	3.145772	4.706688	12.705186	-0.595810	1.142058	0.078873
+3.060447	3.473756	4.627685	13.078657	-0.563568	1.099691	0.082737
+3.061449	3.612611	4.539105	13.279756	-0.535590	1.061320	0.084335
+3.062411	3.727525	4.481648	13.282150	-0.509077	1.028012	0.084069
+3.063379	3.789770	4.445738	13.157660	-0.481764	1.003764	0.085002
+3.064356	3.844833	4.455314	13.217511	-0.457783	0.985245	0.084868
+3.065411	3.854409	4.381099	13.107385	-0.426606	0.972055	0.074476
+3.066404	3.842439	4.318854	12.777007	-0.371315	0.962729	0.052626
+3.067510	4.026780	4.311671	12.870375	-0.350665	0.971655	0.035706
+3.068509	4.493619	4.235062	14.407351	-0.440196	1.003231	0.058489
+3.069513	4.175211	3.928625	14.900523	-0.559971	1.045332	0.089798
+3.070509	3.868773	3.320538	15.017832	-0.658296	1.081305	0.106585
+3.071508	3.660492	3.023676	14.689848	-0.685741	1.085568	0.103521
+3.072509	3.775406	2.829759	14.850249	-0.648703	1.038804	0.091263
+3.073462	3.950171	2.496987	14.888553	-0.603271	0.960730	0.078074
+3.074494	4.086631	2.403619	14.500718	-0.584485	0.897845	0.068747
+3.075509	4.093813	2.470652	14.232585	-0.581288	0.852813	0.063152
+3.076509	3.986082	2.341374	14.246950	-0.575959	0.809380	0.060087
+3.077513	3.799346	2.070847	14.438473	-0.560504	0.755554	0.051294
+3.078509	3.588670	1.850595	14.268496	-0.539986	0.694801	0.039570
+3.079508	3.406723	1.723711	13.782505	-0.527196	0.644173	0.026247
+3.080423	3.174501	1.668648	13.435369	-0.526796	0.606069	0.015055
+3.081418	2.894398	1.568098	12.987683	-0.535590	0.581021	0.005995
+3.082394	2.623871	1.489095	12.798554	-0.539986	0.554109	-0.000666
+3.083407	2.307857	1.323906	12.834464	-0.536655	0.520401	-0.006262
+3.084394	2.056483	1.089290	12.796160	-0.525997	0.481498	-0.009060
+3.085413	1.778774	0.842703	12.652517	-0.513606	0.448323	-0.006528
+3.086412	1.424456	0.624845	12.324533	-0.505746	0.424608	-0.003864
+3.087438	1.134776	0.447686	12.099493	-0.499617	0.407421	0.001066
+3.088507	0.878614	0.323196	11.905576	-0.493089	0.393032	0.005329
+3.089508	0.682302	0.086186	11.819390	-0.486294	0.381441	0.012790
+3.090508	0.428534	-0.090974	11.630261	-0.479366	0.372515	0.021717
+3.091515	0.217858	-0.263345	11.493800	-0.474303	0.367052	0.034640
+3.092446	0.023940	-0.418958	11.304671	-0.468841	0.367452	0.054492
+3.093516	-0.074215	-0.581752	11.139482	-0.463378	0.366786	0.075009
+3.094462	-0.153219	-0.663150	11.151452	-0.456317	0.362655	0.096992
+3.095508	-0.208282	-0.830733	11.110753	-0.442061	0.351464	0.123239
+3.096456	-0.203494	-1.055773	11.019780	-0.426207	0.333611	0.150152
+3.097405	-0.138854	-1.218568	11.003021	-0.409020	0.316158	0.174266
+3.098399	-0.198706	-1.292783	10.792346	-0.393032	0.298438	0.194518
+3.099399	-0.292073	-1.434032	10.576882	-0.378643	0.279786	0.215835
+3.100400	-0.268133	-1.510641	10.454786	-0.365187	0.257270	0.234221
+3.101372	-0.361500	-1.484307	10.303961	-0.358392	0.237418	0.249142
+3.102410	-0.478809	-1.441214	10.203411	-0.355328	0.223828	0.259002
+3.103408	-0.533872	-1.414879	10.086103	-0.355861	0.213570	0.263398
+3.104449	-0.672726	-1.321512	9.973583	-0.361323	0.207974	0.264997
+3.105449	-0.821157	-1.206598	9.937672	-0.367052	0.204243	0.265530
+3.106447	-0.857067	-1.197021	9.947249	-0.373181	0.200380	0.265930
+3.107448	-0.904948	-1.096472	9.952037	-0.380642	0.202645	0.260334
+3.108447	-0.979164	-1.043803	9.863457	-0.390234	0.210239	0.248876
+3.109449	-0.938465	-0.976770	9.772483	-0.400626	0.219565	0.232755
+3.110447	-1.048591	-0.907342	9.784454	-0.411285	0.227959	0.214502
+3.111442	-1.084501	-0.859461	9.825152	-0.419678	0.235020	0.193452
+3.112431	-1.022256	-0.813975	9.885003	-0.426606	0.242614	0.170669
+3.113374	-0.967193	-0.720607	9.896974	-0.436865	0.254205	0.146554
+3.114370	-0.881008	-0.639209	9.875427	-0.447657	0.266196	0.124971
+3.115369	-0.871432	-0.531478	9.925702	-0.458315	0.277387	0.103654
+3.116448	-0.849885	-0.514719	9.971189	-0.469773	0.289778	0.081671
+3.117420	-0.794822	-0.524295	10.023858	-0.482164	0.302968	0.063152
+3.118447	-0.706243	-0.474021	10.057375	-0.494288	0.315625	0.047697
+3.119419	-0.564994	-0.438110	10.133984	-0.505879	0.326550	0.036505
+3.120448	-0.507537	-0.378259	10.160318	-0.515738	0.333611	0.026646
+3.121433	-0.395017	-0.344742	10.232140	-0.523066	0.341072	0.017986
+3.122448	-0.272921	-0.380653	10.342266	-0.530926	0.346801	0.013456
+3.123448	-0.134066	-0.351924	10.500272	-0.536522	0.349599	0.012524
+3.124410	0.052669	-0.275315	10.591246	-0.541585	0.351864	0.011458
+3.125509	0.191523	-0.294467	10.634339	-0.544250	0.352530	0.012790
+3.126509	0.323196	-0.248980	10.660673	-0.545715	0.352663	0.015588
+3.127424	0.430928	-0.246586	10.660673	-0.543983	0.350665	0.018519
+3.128425	0.471626	-0.263345	10.751647	-0.540119	0.346934	0.022516
+3.129467	0.567388	-0.201100	10.787558	-0.534391	0.342804	0.025314
+3.130447	0.699061	-0.172371	10.773193	-0.526930	0.338008	0.027312
+3.131430	0.713425	-0.167583	10.797134	-0.519469	0.330547	0.025447
+3.132434	0.699061	-0.172371	10.761223	-0.511741	0.323752	0.022116
+3.133416	0.701455	-0.146037	10.742071	-0.503214	0.320688	0.020251
+3.134413	0.672726	-0.098156	10.773193	-0.494421	0.317890	0.018652
+3.135422	0.622451	-0.016758	10.847409	-0.485628	0.315092	0.015322
+3.136430	0.627239	-0.045487	10.737283	-0.476835	0.311095	0.010925
+3.137467	0.545842	-0.014364	10.816286	-0.467508	0.306698	0.003597
+3.138467	0.538660	0.031123	10.782770	-0.459248	0.303501	-0.002531
+3.139464	0.562600	0.126884	10.763617	-0.450322	0.300436	-0.008793
+3.140457	0.581752	0.217858	10.801922	-0.440729	0.297505	-0.014123
+3.141468	0.564994	0.316014	10.732495	-0.434467	0.295240	-0.018253
+3.142410	0.584146	0.383047	10.847409	-0.429538	0.293109	-0.019052
+3.143467	0.591329	0.423746	10.845015	-0.425008	0.291510	-0.018253
+3.144415	0.663150	0.490779	10.878531	-0.418746	0.288446	-0.019452
+3.145437	0.813975	0.476415	10.799528	-0.412084	0.282983	-0.019851
+3.146450	0.869038	0.543448	10.833044	-0.404757	0.280319	-0.018919
+3.147391	0.912130	0.600905	10.847409	-0.399028	0.280718	-0.016387
+3.148388	1.019862	0.615269	10.876137	-0.393432	0.274190	-0.011991
+3.149439	1.094078	0.624845	10.919230	-0.386237	0.263665	-0.009326
+3.150434	1.091684	0.670332	10.955141	-0.377311	0.254205	-0.005462
+3.151434	1.070137	0.703849	11.036538	-0.366386	0.241015	0.000533
+3.152436	1.084501	0.634421	11.105965	-0.357593	0.224894	0.007194
+3.153512	0.991134	0.620057	11.060479	-0.350398	0.208107	0.016254
+3.154478	0.861855	0.675120	10.959929	-0.344403	0.189588	0.028112
+3.155451	0.864250	0.643998	10.981475	-0.342404	0.174000	0.038637
+3.156511	0.986346	0.634421	11.062873	-0.344136	0.164274	0.040636
+3.157512	1.187445	0.744547	10.950353	-0.344003	0.158545	0.035040
+3.158508	1.254479	0.737365	10.861773	-0.340539	0.155881	0.027179
+3.159508	1.230538	0.732577	11.010204	-0.342138	0.157346	0.023049
+3.160510	1.106048	0.600905	11.240032	-0.342937	0.156946	0.022516
+3.161465	0.969587	0.538660	11.168210	-0.338274	0.151484	0.024248
+3.162508	0.852279	0.505143	10.940776	-0.332012	0.144156	0.024648
+3.163447	0.763700	0.519507	10.919230	-0.316957	0.134031	0.021317
+3.164411	0.785246	0.387835	10.849803	-0.298571	0.124172	0.016121
+3.165429	0.828339	0.318408	10.715736	-0.274723	0.119775	0.004397
+3.166424	0.902554	0.201100	11.031750	-0.273657	0.123372	-0.004663
+3.167424	1.077319	-0.016758	11.749963	-0.323352	0.129634	0.000666
+3.168424	0.864250	0.203494	11.702082	-0.375712	0.131100	0.011058
+3.169422	0.737365	0.287285	11.292701	-0.392100	0.127103	0.015322
+3.170478	0.916918	0.363895	10.914442	-0.396363	0.127636	0.017320
+3.171428	1.240114	0.658362	10.947958	-0.423142	0.143490	0.029178
+3.172508	1.434032	0.981558	11.065267	-0.474703	0.182127	0.057556
+3.173510	0.770882	0.770882	10.849803	-0.515871	0.224761	0.074476
+3.174445	-0.009576	0.074215	10.378176	-0.534391	0.253273	0.062485
+3.175506	-0.311226	-0.438110	10.198623	-0.534923	0.261000	0.037704
+3.176512	-0.442898	-0.660756	10.488302	-0.527196	0.246877	0.015322
+3.177513	-0.466838	-0.639209	10.648703	-0.516005	0.219165	-0.006795
+3.178508	-0.507537	-0.679908	10.883319	-0.496953	0.185591	-0.034107
+3.179512	-0.418958	-0.655968	10.962323	-0.474436	0.152017	-0.065417
+3.180452	-0.416563	-0.608087	10.777981	-0.458982	0.128168	-0.093795
+3.181418	-0.361500	-0.531478	10.636733	-0.444859	0.114446	-0.120974
+3.182417	-0.416563	-0.529083	10.512243	-0.432335	0.108450	-0.147887
+3.183401	-0.418958	-0.452474	10.380570	-0.420078	0.106718	-0.170003
+3.184401	-0.548236	-0.392623	10.078921	-0.413283	0.114579	-0.189055
+3.185368	-0.562600	-0.287285	9.719814	-0.414616	0.132299	-0.198914
+3.186446	-0.643998	-0.196312	9.885003	-0.416614	0.151217	-0.212237
+3.187449	-0.718213	-0.069427	9.992735	-0.416881	0.165473	-0.220098
+3.188401	-0.737365	-0.011970	10.043010	-0.413949	0.178263	-0.228758
+3.189392	-0.691878	0.047881	9.940066	-0.410485	0.193585	-0.235553
+3.190445	-0.706243	0.122096	9.705450	-0.409286	0.210505	-0.239017
+3.191449	-0.703849	0.232222	9.655175	-0.413816	0.227159	-0.242881
+3.192448	-0.785246	0.378259	9.351132	-0.427006	0.246611	-0.247011
+3.193450	-0.821157	0.387835	9.286493	-0.439530	0.270060	-0.251674
+3.194448	-0.691878	0.406987	9.422953	-0.447790	0.289645	-0.257802
+3.195428	-0.600905	0.287285	9.394225	-0.453652	0.306698	-0.265930
+3.196393	-0.229828	0.277709	9.470834	-0.458715	0.334810	-0.286580
+3.197433	0.011970	0.268133	9.715026	-0.458582	0.375579	-0.313493
+3.198435	-0.229828	0.191523	9.873033	-0.451387	0.397695	-0.322286
+3.199436	-0.598511	0.043093	9.837123	-0.440329	0.396763	-0.312827
+3.200434	-0.967193	-0.026334	9.738967	-0.431003	0.397029	-0.302035
+3.201436	-0.967193	-0.026334	9.738967	-0.425940	0.401825	-0.293642
+3.202435	-1.101260	-0.112520	9.595324	-0.416747	0.393698	-0.284982
+3.203508	-1.062955	-0.215464	9.712632	-0.400493	0.375312	-0.279253
+3.204509	-1.058167	-0.263345	9.930490	-0.383306	0.356394	-0.276188
+3.205464	-1.027044	-0.246586	10.047798	-0.366919	0.343337	-0.274190
+3.206460	-0.873826	-0.227434	10.009494	-0.350132	0.335876	-0.275389
+3.207511	-0.632027	-0.248980	9.985553	-0.334677	0.328282	-0.276988
+3.208507	-0.502749	-0.284891	9.937672	-0.327083	0.325750	-0.274456
+3.209513	-0.481203	-0.222646	9.719814	-0.324685	0.324285	-0.271259
+3.210509	-0.469232	-0.184341	9.609688	-0.322953	0.322819	-0.266729
+3.211507	-0.452474	-0.229828	9.530685	-0.319489	0.321221	-0.262732
+3.212506	-0.342348	-0.320802	9.430135	-0.313493	0.320155	-0.264864
+3.213462	-0.227434	-0.385441	9.521109	-0.304700	0.323352	-0.271792
+3.214440	-0.114914	-0.435716	9.533079	-0.292443	0.324152	-0.278320
+3.215410	-0.129278	-0.588935	9.573778	-0.274057	0.316158	-0.278587
+3.216437	-0.227434	-0.708637	9.700662	-0.254605	0.304567	-0.277387
+3.217401	-0.406987	-0.763700	9.710238	-0.236885	0.293642	-0.278587
+3.218394	-0.502749	-0.876220	9.779666	-0.214369	0.278720	-0.287247
+3.219398	-0.383047	-0.945647	9.973583	-0.189721	0.263265	-0.299371
+3.220480	-0.241798	-0.847491	9.949643	-0.168671	0.254605	-0.310562
+3.221482	-0.136460	-0.732577	9.777271	-0.150551	0.250608	-0.321620
+3.222480	-0.081397	-0.620057	9.750937	-0.137095	0.250874	-0.328681
+3.223479	-0.047881	-0.502749	9.770089	-0.124172	0.252074	-0.331346
+3.224479	-0.095762	-0.430928	9.779666	-0.114979	0.248876	-0.329214
+3.225446	-0.117308	-0.294467	9.667146	-0.109516	0.239283	-0.321753
+3.226479	-0.079003	-0.344742	9.487592	-0.095127	0.217567	-0.308963
+3.227480	0.021546	-0.469232	9.473228	-0.077274	0.200646	-0.297106
+3.228482	0.114914	-0.220252	9.748543	-0.069147	0.199847	-0.291110
+3.229467	0.062245	0.124490	9.877821	-0.068881	0.207308	-0.288312
+3.230401	0.033517	0.299255	9.865851	-0.076741	0.213170	-0.287113
+3.231395	0.009576	0.399805	9.784454	-0.088599	0.218899	-0.284182
+3.232394	-0.093368	0.447686	9.525897	-0.098058	0.224361	-0.279652
+3.233412	-0.090974	0.519507	9.516321	-0.100989	0.222629	-0.270326
+3.234380	-0.043093	0.497961	9.612083	-0.098991	0.218632	-0.263132
+3.235452	-0.069427	0.502749	9.676722	-0.099124	0.216368	-0.259534
+3.236435	-0.102944	0.545842	9.755725	-0.101789	0.214103	-0.256470
+3.237488	-0.093368	0.553024	9.746149	-0.107518	0.216234	-0.254338
+3.238499	-0.086186	0.617663	9.600112	-0.115911	0.222230	-0.251008
+3.239498	-0.119702	0.672726	9.516321	-0.118176	0.225427	-0.246345
+3.240469	-0.169977	0.639209	9.664751	-0.113779	0.224361	-0.238884
+3.241501	-0.174765	0.660756	9.636023	-0.112181	0.225028	-0.233688
+3.242499	-0.095762	0.687090	9.566596	-0.109649	0.223296	-0.229158
+3.243499	-0.079003	0.639209	9.628841	-0.105652	0.219565	-0.223429
+3.244498	-0.155613	0.658362	9.516321	-0.101123	0.214236	-0.218366
+3.245428	-0.100550	0.684696	9.533079	-0.096060	0.209573	-0.215701
+3.246434	-0.052669	0.739759	9.564202	-0.093662	0.204910	-0.209839
+3.247416	-0.040699	0.813975	9.513927	-0.092063	0.200913	-0.204510
+3.248416	-0.098156	0.828339	9.454076	-0.086600	0.195317	-0.199314
+3.249430	-0.064639	0.823551	9.561808	-0.075276	0.186923	-0.194651
+3.250424	-0.035911	0.794822	9.703056	-0.064750	0.178796	-0.191853
+3.251420	0.023940	0.811581	9.734179	-0.060354	0.173067	-0.190121
+3.252431	0.002394	0.720607	9.518715	-0.060887	0.168271	-0.189188
+3.253510	-0.093368	0.763700	9.442105	-0.061686	0.162409	-0.183593
+3.254489	-0.131672	0.790034	9.566596	-0.058755	0.156413	-0.178796
+3.255448	-0.225040	0.742153	9.628841	-0.054625	0.153083	-0.175066
+3.256509	-0.294467	0.696667	9.530685	-0.051161	0.155481	-0.168671
+3.257513	-0.313620	0.632027	9.614477	-0.046631	0.157213	-0.161476
+3.258510	-0.294467	0.529083	9.691086	-0.043433	0.157879	-0.154681
+3.259506	-0.301649	0.418958	9.638417	-0.038104	0.158945	-0.145089
+3.260509	-0.320802	0.375865	9.561808	-0.031309	0.158279	-0.135763
+3.261508	-0.301649	0.253769	9.554625	-0.019452	0.153083	-0.132432
+3.262509	-0.265739	0.146037	9.650387	-0.007461	0.147087	-0.128435
+3.263452	-0.342348	0.098156	9.612083	0.001466	0.144156	-0.125770
+3.264401	-0.339954	0.043093	9.573778	0.009992	0.144956	-0.123239
+3.265422	-0.301649	0.007182	9.518715	0.022383	0.143757	-0.120175
+3.266424	-0.344742	0.019152	9.545049	0.035306	0.140159	-0.117910
+3.267425	-0.399805	-0.004788	9.647993	0.048230	0.136962	-0.117910
+3.268425	-0.450080	-0.026334	9.580960	0.060354	0.133498	-0.112314
+3.269385	-0.462050	-0.014364	9.485198	0.069813	0.134963	-0.106985
+3.270392	-0.588935	0.026334	9.288887	0.074609	0.139227	-0.102455
+3.271447	-0.586541	-0.095762	9.147638	0.063818	0.136962	-0.073810
+3.272444	-0.004788	-1.436426	9.027936	0.081804	0.128701	-0.065417
+3.273444	-0.320802	-0.327984	9.114122	0.098325	0.137228	-0.079139
+3.274405	-1.311936	0.282497	9.837123	0.071012	0.168138	-0.081005
+3.275467	-1.079713	-0.718213	9.631235	0.027979	0.212104	-0.064750
+3.276442	-0.675120	-0.998316	9.035118	0.014789	0.252740	-0.063152
+3.277449	-1.493883	-0.143643	8.999208	-0.004397	0.296306	-0.073677
+3.278449	-1.795532	-0.057457	9.250582	-0.050761	0.340672	-0.075142
+3.279392	-1.208992	-0.244192	9.097363	-0.093662	0.374380	-0.063951
+3.280359	-0.794822	-0.548236	8.948933	-0.114179	0.386904	-0.035040
+3.281436	-0.138854	-1.079713	8.994419	-0.104587	0.383306	-0.016521
+3.282434	-0.184341	-1.129988	9.226642	-0.053292	0.349732	-0.026913
+3.283435	-0.696667	-1.580068	9.320009	-0.011325	0.312427	-0.057689
+3.284395	-0.962405	-1.436426	9.738967	-0.052227	0.343737	-0.077940
+3.285438	-0.952829	-0.167583	10.440421	-0.123372	0.404490	-0.042634
+3.286417	-0.057457	-1.153929	9.604900	-0.100989	0.394364	-0.002398
+3.287410	0.383047	-1.900870	8.527581	-0.032775	0.334144	-0.009593
+3.288421	-0.445292	-1.331088	9.233824	-0.019585	0.318423	-0.053159
+3.289412	-1.366999	0.098156	10.562518	-0.099124	0.376778	-0.066749
+3.290409	-0.876220	0.421352	10.655885	-0.148953	0.427006	-0.056890
+3.291402	-0.701455	0.459656	9.762907	-0.130433	0.420744	-0.056623
+3.292416	-0.806792	-0.227434	9.396619	-0.135763	0.413150	-0.059954
+3.293383	-0.794822	-0.529083	9.786848	-0.125371	0.399827	-0.065550
+3.294382	-0.775670	-0.713425	9.243400	-0.064351	0.338141	-0.072744
+3.295383	-0.632027	-1.381363	8.951327	-0.020518	0.269926	-0.081538
+3.296359	-0.500355	-1.237720	9.724603	-0.025847	0.249942	-0.084069
+3.297379	-0.471626	-0.435716	10.385358	-0.194917	0.365853	-0.101389
+3.298375	-1.635131	-0.591329	11.778691	-0.423809	0.601406	-0.146421
+3.299382	-3.435452	-1.534582	10.560124	-0.547580	0.799387	-0.157213
+3.300367	-2.348556	-1.838625	9.121304	-0.562902	0.868801	-0.126303
+3.301383	-1.309542	-2.157033	8.810078	-0.545049	0.840023	-0.083270
+3.302377	-0.363895	-2.269553	9.659963	-0.527462	0.776072	-0.063551
+3.303377	0.337560	-2.109152	10.687008	-0.488959	0.694401	-0.070213
+3.304378	0.591329	-2.169003	11.103571	-0.467775	0.626986	-0.078473
+3.305428	0.878614	-1.730893	11.532105	-0.471106	0.604204	-0.078873
+3.306432	0.780458	-1.280813	11.510559	-0.449123	0.587550	-0.078473
+3.307413	0.356712	-1.771592	10.904866	-0.429671	0.554908	-0.083403
+3.308431	0.308832	-1.723711	10.912048	-0.434067	0.518936	-0.075276
+3.309435	0.433322	-1.029438	11.165816	-0.421144	0.480965	-0.069547
+3.310415	0.277709	-1.161111	10.938382	-0.347867	0.368118	-0.082070
+3.311434	0.119702	-1.800320	13.885449	0.007727	-0.114579	-0.122839
+3.312414	0.471626	-3.512061	23.595687	0.327083	-0.537055	-0.166406
+3.313420	1.908052	-3.064375	21.125035	0.366919	-0.457783	-0.171202
+3.314410	1.479519	-0.586541	11.345370	0.282184	-0.187057	-0.149885
+3.315412	1.230538	-0.229828	7.170159	0.275123	-0.173467	-0.141492
+3.316416	1.254479	-1.915234	10.579276	0.291243	-0.262732	-0.154015
+3.317401	1.436426	-2.152245	10.888107	0.296573	-0.259002	-0.161077
+3.318379	1.457972	-1.797926	9.774877	0.324685	-0.237152	-0.163608
+3.319387	0.993528	-1.704559	10.007100	0.370383	-0.268727	-0.123106
+3.320384	0.002394	-0.086186	10.926412	0.278453	-0.255271	-0.066749
+3.321389	0.569782	1.615979	12.257500	0.219432	-0.229691	-0.050228
+3.322397	-0.359106	0.383047	9.887397	0.228492	-0.247410	-0.051827
+3.323397	-1.211386	0.071821	9.609688	0.226360	-0.275789	-0.056890
+3.324354	-1.034227	-0.189129	9.640811	0.202645	-0.307897	-0.068614
+3.325373	0.342348	0.043093	10.505061	0.181594	-0.315358	-0.056224
+3.326407	0.813975	1.094078	10.552941	0.165740	-0.294974	-0.029311
+3.327397	0.217858	1.446002	10.086103	0.177064	-0.294574	-0.000933
+3.328400	-0.675120	0.615269	9.547443	0.193985	-0.330547	0.000400
+3.329433	-0.189129	-0.160401	9.379860	0.203178	-0.359991	-0.010925
+3.330411	0.114914	-0.222646	8.869929	0.208640	-0.367585	0.006262
+3.331409	-0.268133	0.658362	9.087787	0.215035	-0.372115	0.036106
+3.332399	-0.509931	0.615269	9.444500	0.225161	-0.384905	0.047297
+3.333375	-0.332772	0.280103	9.365496	0.243813	-0.393032	0.048363
+3.334369	-0.026334	0.636815	8.970479	0.270992	-0.398095	0.065017
+3.335373	-0.016758	1.328694	9.001602	0.276055	-0.392899	0.068214
+3.336389	-0.043093	1.007892	9.229036	0.244213	-0.360524	0.032508
+3.337369	-0.447686	0.330378	9.540261	0.218233	-0.312294	-0.013323
+3.338386	-0.878614	0.359106	10.028646	0.222629	-0.277254	-0.031443
+3.339385	-1.304753	0.914524	10.591246	0.248876	-0.263265	-0.014389
+3.340391	-1.177869	1.548946	10.976687	0.257669	-0.247277	0.007061
+3.341391	-0.938465	1.153929	10.567306	0.226493	-0.202378	-0.008793
+3.342389	-0.981558	0.100550	9.875427	0.203444	-0.161476	-0.052626
+3.343366	-0.787640	0.129278	10.323113	0.215435	-0.159345	-0.091130
+3.344390	0.004788	0.560206	10.962323	0.229824	-0.156413	-0.103654
+3.345390	0.416563	0.636815	10.519425	0.214902	-0.122972	-0.111115
+3.346366	0.471626	0.313620	9.810788	0.189588	-0.084202	-0.131899
+3.347368	0.512325	0.316014	9.918520	0.172934	-0.063818	-0.157746
+3.348376	0.603299	0.392623	10.150742	0.162675	-0.049962	-0.170936
+3.349395	0.339954	0.459656	10.303961	0.157613	-0.036772	-0.172801
+3.350393	0.239404	0.588935	10.375782	0.137761	-0.012790	-0.179862
+3.351408	0.122096	0.141249	9.947249	0.123639	0.006129	-0.184525
+3.352395	-0.299255	0.373471	10.260868	0.083936	-0.027979	-0.179862
+3.353396	-0.763700	0.976770	11.644625	0.019185	-0.081538	-0.172934
+3.354386	-0.797216	1.541764	11.120330	-0.012257	-0.069413	-0.152283
+3.355390	-0.351924	1.469942	9.750937	-0.007194	-0.034507	-0.123905
+3.356368	-0.153219	0.926495	10.129196	0.019185	-0.019452	-0.112047
+3.357361	0.258557	0.189129	10.361418	0.031842	-0.011591	-0.119242
+3.358356	0.335166	0.009576	10.155530	0.022916	-0.009060	-0.135896
+3.359359	-0.035911	0.198706	10.088497	0.005196	-0.015188	-0.147620
+3.360360	-0.213070	0.287285	9.971189	-0.010392	-0.018253	-0.151217
+3.361360	-0.193917	0.292073	9.688692	-0.025447	-0.013723	-0.152683
+3.362373	-0.189129	0.167583	9.454076	-0.027046	-0.013989	-0.149885
+3.363358	-0.074215	0.167583	9.545049	-0.014123	-0.015855	-0.144689
+3.364347	0.114914	0.023940	9.655175	-0.004530	-0.020784	-0.150951
+3.365361	-0.095762	-0.179553	9.741361	-0.001066	-0.027579	-0.162009
+3.366376	-0.368683	-0.272921	9.533079	0.003464	-0.034907	-0.170136
+3.367415	-0.509931	-0.332772	9.600112	0.017320	-0.044366	-0.171735
+3.368393	-0.746941	-0.349530	9.779666	0.024781	-0.051161	-0.180262
+3.369450	-0.708637	-0.608087	9.710238	0.022516	-0.065816	-0.189855
+3.370440	-1.371787	-0.146037	9.913732	0.012790	-0.086734	-0.187456
+3.371447	-1.347846	0.167583	9.806000	-0.001599	-0.096859	-0.174000
+3.372391	-0.835521	0.045487	9.401407	-0.019452	-0.081138	-0.158678
+3.373450	-0.287285	-0.019152	9.674328	-0.025314	-0.047697	-0.148153
+3.374449	0.277709	-0.179553	9.920914	-0.014123	-0.036905	-0.152417
+3.375449	0.545842	-0.665544	9.913732	-0.005596	-0.033574	-0.165340
+3.376395	0.100550	-0.794822	9.719814	-0.005729	-0.030510	-0.176665
+3.377414	-0.284891	-0.837915	9.662357	-0.008527	-0.023049	-0.184126
+3.378409	-0.378259	-0.914524	9.700662	-0.011058	-0.019851	-0.185191
+3.379409	-0.581752	-0.957617	9.772483	-0.009459	-0.020518	-0.176798
+3.380377	-0.564994	-0.909736	9.791636	-0.001998	-0.022250	-0.166539
+3.381362	-0.509931	-1.058167	9.841911	0.003464	-0.020384	-0.169070
+3.382362	-0.268133	-1.429244	9.691086	0.009326	-0.017587	-0.173600
+3.383450	-0.174765	-1.232932	9.863457	0.013989	-0.008926	-0.176531
+3.384363	0.011970	-1.158717	9.801212	0.019585	0.003997	-0.162809
+3.385409	-0.351924	-0.591329	9.952037	0.022649	0.016254	-0.139360
+3.386450	-0.450080	-0.576964	9.837123	0.018919	0.021450	-0.129900
+3.387449	-0.253769	-1.125200	9.583354	0.012923	0.019319	-0.127636
+3.388401	-0.196312	-0.945647	9.528291	0.010925	0.012257	-0.122040
+3.389365	-0.035911	-0.723001	9.576172	0.011058	0.016920	-0.105519
+3.390393	-0.270527	-0.502749	9.628841	0.013856	0.027179	-0.088066
+3.391385	-0.375865	-0.339954	10.028646	0.015055	0.038237	-0.077674
+3.392403	-0.395017	-0.366289	9.978371	0.009326	0.037704	-0.080738
+3.393400	-0.699061	-0.715819	9.595324	0.002665	0.031309	-0.094994
+3.394385	-1.096472	-0.981558	9.415771	0.001466	0.038770	-0.105519
+3.395449	-0.967193	-0.629633	9.832334	0.008660	0.052493	-0.105652
+3.396369	-0.610481	-0.617663	9.990341	0.011858	0.051161	-0.104986
+3.397363	-0.251375	-1.005498	9.703056	-0.000533	0.023982	-0.106585
+3.398362	-0.361500	-0.684696	9.667146	-0.018786	0.000400	-0.103920
+3.399407	-0.588935	0.158007	9.798818	-0.037571	-0.014256	-0.099790
+3.400405	-0.598511	-0.093368	9.535473	-0.040502	-0.021450	-0.106718
+3.401423	-1.027044	-0.294467	9.628841	-0.022116	-0.012257	-0.123372
+3.402451	-1.927205	0.756518	10.500272	0.000133	0.001466	-0.107917
+3.403451	-1.072531	1.180263	10.210593	0.007194	0.002265	-0.084868
+3.404452	0.488385	-0.088580	9.454076	0.009060	-0.008127	-0.091397
+3.405452	0.651180	-0.667938	9.789242	0.016920	-0.013856	-0.112580
+3.406451	0.828339	-0.924101	10.062163	0.027579	-0.023315	-0.122573
+3.407451	0.859461	-0.785246	10.052586	0.031043	-0.024248	-0.122972
+3.408449	1.127594	-0.701455	9.861063	0.018119	-0.008926	-0.110049
+3.409452	1.254479	-0.732577	9.750937	0.012391	-0.008926	-0.101123
+3.410396	0.651180	-0.773276	9.844305	0.024115	-0.028645	-0.092729
+3.411445	0.713425	-1.039015	9.880215	0.040369	-0.045698	-0.068881
+3.412451	0.885796	-0.974375	9.817970	0.044366	-0.047963	-0.033974
+3.413393	1.122806	-0.615269	9.779666	0.034107	-0.034907	0.005596
+3.414375	1.273631	-0.193917	9.750937	0.034374	-0.032242	0.048230
+3.415357	1.278419	0.014364	9.930490	0.045032	-0.036505	0.090597
+3.416403	1.663860	-0.181947	9.724603	0.065017	-0.048629	0.129900
+3.417450	2.018178	-0.179553	9.444500	0.080072	-0.052760	0.175066
+3.418450	1.498671	0.112520	9.578566	0.080605	-0.062885	0.206375
+3.419452	0.277709	0.050275	10.059769	0.073011	-0.062885	0.216234
+3.420458	-0.495567	-0.165189	9.686298	0.070213	-0.075142	0.211571
+3.421408	-1.522611	0.088580	10.026252	0.087533	-0.136562	0.194784
+3.422450	-1.790744	0.155613	10.244110	0.099257	-0.143090	0.184925
+3.423450	-0.835521	1.197021	9.949643	0.065550	-0.070479	0.173467
+3.424410	-0.294467	1.201810	9.449288	0.060753	-0.040369	0.163342
+3.425452	-0.272921	0.933677	9.600112	0.070213	-0.045832	0.142957
+3.426443	0.193917	0.940859	9.880215	0.093662	-0.053692	0.133631
+3.427451	-0.466838	0.904948	9.647993	0.122040	-0.084202	0.152683
+3.428451	-0.957617	0.457262	9.233824	0.116711	-0.096992	0.170403
+3.429397	-0.519507	0.181947	9.267340	0.108583	-0.079939	0.173334
+3.430377	-0.636815	0.869038	9.916126	0.112847	-0.089798	0.170003
+3.431373	-1.232932	0.653574	10.229746	0.102855	-0.090597	0.174933
+3.432375	-1.139564	0.924101	9.638417	0.117510	-0.101922	0.179462
+3.433454	-0.581752	1.400515	10.026252	0.128168	-0.106185	0.174933
+3.434407	-0.004788	1.194627	9.695874	0.092596	-0.098058	0.151617
+3.435403	0.414169	0.660756	8.786138	0.067149	-0.090864	0.135096
+3.436450	-0.727789	1.745257	10.459574	0.055557	-0.042634	0.130300
+3.437452	-0.780458	1.747651	10.299173	0.062352	-0.036905	0.122706
+3.438451	0.423746	0.497961	8.920204	0.065683	-0.070613	0.113513
+3.439453	1.163505	0.076609	8.987237	0.042634	-0.055557	0.106585
+3.440407	0.327984	1.022256	10.280021	0.021450	0.002931	0.104986
+3.441422	-0.648786	1.438820	10.394935	0.004930	0.031043	0.097259
+3.442408	-0.071821	0.385441	9.267340	-0.010925	0.029444	0.088599
+3.443450	0.359106	0.337560	9.308039	-0.012391	0.016121	0.077940
+3.444451	-0.186735	0.512325	10.040616	0.000133	-0.001066	0.065949
+3.445451	-0.248980	0.641604	10.191441	0.004930	-0.006129	0.063285
+3.446447	0.320802	0.672726	9.681510	-0.000133	0.002931	0.065550
+3.447378	0.696667	0.756518	9.391831	-0.007328	0.014922	0.061286
+3.448373	1.039015	0.624845	9.501957	-0.010925	0.024515	0.047164
+3.449369	0.813975	0.744547	9.782060	-0.006395	0.035839	0.045832
+3.450451	-0.055063	1.024650	9.911338	0.005596	0.038770	0.063551
+3.451452	-0.833127	0.754124	9.693480	0.015988	0.035440	0.078074
+3.452449	-1.656678	0.457262	9.892186	0.023315	0.026247	0.093662
+3.453441	-2.647812	0.311226	10.043010	0.015188	0.020917	0.097792
+3.454473	-2.200125	-0.002394	9.808394	0.004663	0.025847	0.097925
+3.455445	-0.828339	0.246586	9.612083	0.001998	0.026646	0.109383
+3.456451	0.047881	0.435716	9.681510	0.005596	0.023449	0.128035
+3.457452	0.359106	0.433322	9.791636	0.013190	0.016121	0.131233
+3.458444	0.399805	0.277709	9.932884	0.026779	0.003864	0.118176
+3.459451	1.132382	0.354318	10.014282	0.039836	-0.000533	0.105253
+3.460449	2.283917	0.864250	10.011888	0.047297	0.000666	0.101922
+3.461451	2.583172	1.103654	9.810788	0.042634	-0.001332	0.092063
+3.462450	2.688510	0.979164	9.612083	0.042900	-0.022250	0.053426
+3.463397	3.047617	1.082107	10.083709	0.011858	-0.016787	-0.002398
+3.464377	2.209702	1.970297	9.961613	-0.069147	0.022116	-0.056757
+3.465374	0.957617	2.075635	8.972873	-0.099257	0.040636	-0.006262
+3.466450	-1.546552	1.230538	8.989631	-0.042234	-0.016254	0.089665
+3.467445	-1.532187	0.134066	10.634339	0.055824	-0.066083	0.114979
+3.468451	0.679908	-0.253769	11.043720	0.013323	0.034374	0.029044
+3.469452	-1.118018	-0.220252	9.748543	-0.067948	0.153482	-0.023582
+3.470451	-1.929599	1.340664	9.097363	-0.064750	0.143757	0.031309
+3.471445	-0.469232	1.553734	9.446894	-0.008260	0.081138	0.128968
+3.472452	-0.256163	0.629633	9.434923	0.014522	0.070346	0.177464
+3.473395	-1.448396	-0.177159	9.528291	-0.006262	0.097925	0.161609
+3.474452	-3.042829	-0.227434	9.798818	0.000266	0.087000	0.155614
+3.475450	-2.066059	-0.100550	9.784454	0.017187	0.067948	0.177464
+3.476449	-1.122806	-0.076609	9.590536	0.024914	0.073144	0.174400
+3.477453	-0.840309	-0.040699	9.717420	0.030243	0.072078	0.143623
+3.478450	-0.253769	-0.124490	9.719814	0.034374	0.060620	0.112181
+3.479451	0.560206	-0.004788	9.774877	0.041968	0.051427	0.090331
+3.480381	1.254479	-0.215464	9.923308	0.044233	0.059688	0.081538
+3.481363	1.649496	-0.268133	9.688692	0.040369	0.075675	0.086201
+3.482363	1.474730	-0.294467	9.521109	0.036505	0.084335	0.093662
+3.483451	1.050985	-0.265739	9.856275	0.033175	0.089132	0.074743
+3.484406	0.825945	-0.679908	10.205805	0.021850	0.109516	0.037971
+3.485459	0.332772	-1.034227	10.002312	0.016920	0.110982	0.015055
+3.486507	0.696667	-0.325590	10.064557	0.047297	0.073677	0.018919
+3.487507	1.738075	-0.047881	9.794030	0.069547	0.041035	0.030110
+3.488507	1.539370	-0.198706	9.638417	0.068481	0.032109	0.040769
+3.489512	0.842703	-0.241798	9.564202	0.098058	-0.009060	0.070613
+3.490507	0.960011	0.239404	9.875427	0.090198	-0.005462	0.091796
+3.491508	0.404593	-0.313620	9.561808	0.039303	0.045565	0.085534
+3.492507	-0.198706	-0.162795	9.293675	0.007861	0.090464	0.069280
+3.493463	-1.776380	0.802004	9.731785	-0.008926	0.116311	0.063152
+3.494503	-2.432348	0.543448	9.415771	-0.022916	0.115245	0.083136
+3.495509	-2.209702	0.093368	9.303251	-0.034640	0.100590	0.088865
+3.496456	-2.085211	-0.198706	9.798818	-0.034240	0.075675	0.078340
+3.497443	-1.338270	-0.426140	9.913732	-0.029444	0.064217	0.071945
+3.498433	-0.605693	-0.507537	9.786848	-0.037172	0.034107	0.058888
+3.499429	-0.265739	-1.546552	10.512243	-0.029844	-0.052493	0.035573
+3.500435	0.438110	-0.787640	11.134694	0.002798	-0.074210	0.060221
+3.501435	1.453184	0.754124	9.566596	0.014522	-0.035573	0.128302
+3.502434	1.560916	0.749335	8.592220	0.003331	-0.008394	0.180795
+3.503433	1.149141	0.074215	9.059059	-0.009992	-0.011591	0.186257
+3.504459	0.794822	-0.900160	9.504351	-0.015455	-0.041035	0.172135
+3.505506	1.118018	-1.280813	9.456470	-0.022383	-0.057956	0.170536
+3.506442	1.242508	-0.890584	9.207489	-0.039969	-0.011724	0.175332
+3.507508	-0.780458	0.344742	9.406195	-0.041035	0.049029	0.169603
+3.508513	-2.008602	0.713425	9.425347	-0.032642	0.100856	0.173201
+3.509511	-2.123516	-0.021546	8.640101	-0.040502	0.149485	0.195051
+3.510508	-2.865669	-0.782852	9.248188	-0.034907	0.183193	0.222763
+3.511509	-2.973401	-1.089290	9.451682	-0.019052	0.225427	0.231023
+3.512461	-2.078029	-1.563310	8.994419	-0.019585	0.199980	0.206109
+3.513463	-1.843413	-2.140274	11.541681	-0.001865	0.058622	0.127103
+3.514443	-1.510641	-1.943963	12.223983	0.028778	0.008127	0.073943
+3.515434	0.081397	0.129278	10.344660	0.025714	0.040502	0.083136
+3.516430	-0.327984	0.703849	9.406195	-0.014389	0.078740	0.114579
+3.517396	-0.749335	-0.430928	8.711922	-0.040369	0.089398	0.126037
+3.518395	-1.182657	-0.878614	9.631235	-0.030110	0.088466	0.127103
+3.519396	-1.156323	-0.694272	10.246504	-0.005063	0.085534	0.140159
+3.520406	-0.895372	-0.047881	10.143560	0.015588	0.076608	0.159877
+3.521404	-0.655968	-0.007182	9.806000	0.022516	0.067015	0.161343
+3.522406	-0.713425	-0.009576	9.640811	0.018652	0.070346	0.144556
+3.523426	-0.864250	-0.215464	9.750937	0.016787	0.079939	0.125104
+3.524407	-0.806792	-0.107732	9.853881	0.020651	0.086067	0.113247
+3.525474	-0.737365	0.169977	9.820364	0.022250	0.086600	0.102721
+3.526419	-0.744547	0.277709	9.707844	0.013989	0.090331	0.089132
+3.527420	-0.725395	0.136460	9.557020	0.002531	0.090997	0.076075
+3.528419	-0.378259	-0.318408	9.494774	-0.001199	0.090064	0.069680
+3.529410	0.059851	-0.495567	9.633629	0.006395	0.090997	0.060620
+3.530382	0.160401	-0.478809	9.997523	0.017986	0.099790	0.037571
+3.531380	-0.363895	-0.397411	10.086103	0.020784	0.114446	0.003997
+3.532380	-0.758912	-0.052669	9.947249	0.000799	0.136562	-0.020917
+3.533399	-0.799610	0.296861	9.636023	-0.022116	0.153083	-0.025314
+3.534399	-0.471626	0.553024	9.458864	-0.031443	0.155481	-0.019052
+3.535403	-0.169977	0.222646	9.549837	-0.025181	0.149352	-0.021583
+3.536449	-0.081397	0.344742	9.885003	-0.015588	0.140559	-0.019319
+3.537499	-0.136460	0.356712	9.693480	-0.012790	0.135096	-0.007194
+3.538499	-0.330378	0.689484	9.523503	-0.015055	0.134564	0.008527
+3.539497	-0.667938	0.804398	9.542655	-0.027845	0.131366	0.016787
+3.540500	-0.971981	-0.629633	9.516321	-0.028911	0.106985	0.007861
+3.541499	-0.636815	-1.745257	9.841911	-0.013323	0.098724	-0.017986
+3.542498	-0.210676	-1.067743	10.689402	0.005462	0.106319	-0.044100
+3.543436	-0.057457	-0.892978	10.157924	0.002665	0.109116	-0.056357
+3.544417	-0.074215	-0.948041	9.535473	-0.013456	0.106185	-0.060753
+3.545470	-0.181947	-1.283207	9.741361	-0.022916	0.097126	-0.068481
+3.546501	-0.447686	-2.128304	9.901762	-0.018519	0.078606	-0.068348
+3.547402	-0.651180	-1.544158	10.191441	-0.007727	0.063818	-0.052227
+3.548396	-0.557812	-0.857067	10.016676	-0.003198	0.060887	-0.034507
+3.549418	-0.237010	-0.802004	9.537867	-0.006662	0.061686	-0.021983
+3.550413	-0.131672	-0.603299	9.626447	-0.010126	0.059688	-0.011724
+3.551408	-0.165189	-0.603299	9.892186	-0.008660	0.053559	0.004530
+3.552412	-0.153219	-0.459656	9.930490	-0.005862	0.047697	0.026513
+3.553418	-0.069427	-0.421352	9.686298	-0.005729	0.044233	0.046231
+3.554443	0.016758	-0.318408	9.652781	-0.007328	0.042634	0.062485
+3.555437	0.045487	-0.191523	9.808394	-0.006262	0.041302	0.075675
+3.556437	0.033517	-0.186735	9.729391	-0.006129	0.037971	0.088599
+3.557443	0.064639	-0.174765	9.631235	-0.007461	0.035440	0.102588
+3.558442	0.141249	-0.332772	9.633629	-0.008660	0.035839	0.113779
+3.559443	0.090974	-0.521901	9.691086	-0.009593	0.034107	0.130966
+3.560441	0.344742	-0.062245	9.997523	-0.003597	0.023315	0.185724
+3.561441	1.072531	1.314330	10.074133	0.002798	0.010126	0.250874
+3.562437	0.612875	1.623161	9.466046	0.003730	-0.001865	0.299904
+3.563416	-0.526689	0.545842	9.106939	-0.007194	-0.008660	0.280452
+3.564383	-1.706953	-1.185051	9.394225	-0.015322	-0.007594	0.222896
+3.565385	-2.106758	-1.826655	10.083709	-0.009726	-0.007061	0.185458
+3.566384	-1.972691	-1.862565	10.284809	-0.002665	-0.015721	0.178930
+3.567386	-1.764410	-1.582462	9.600112	-0.011724	-0.028511	0.186923
+3.568386	-0.825945	-1.268843	9.142850	-0.022383	-0.035173	0.184392
+3.569400	0.363895	-1.005498	9.480410	-0.021184	-0.033574	0.175865
+3.570399	0.979164	-0.629633	9.896974	-0.005995	-0.030510	0.171469
+3.571398	0.914524	-0.351924	9.978371	0.008793	-0.028511	0.171602
+3.572447	0.392623	-0.265739	9.971189	0.017320	-0.037172	0.184525
+3.573448	-0.007182	-0.167583	9.813182	0.020251	-0.043833	0.194251
+3.574447	-0.095762	-0.359106	9.671934	0.018386	-0.037704	0.182260
+3.575447	-0.476415	-0.648786	9.724603	0.018519	-0.030377	0.165207
+3.576452	-0.562600	-0.241798	9.724603	0.018786	-0.023982	0.151617
+3.577421	-0.478809	0.158007	9.676722	0.016521	-0.018519	0.136429
+3.578449	-0.287285	0.292073	9.705450	0.011991	-0.013057	0.123772
+3.579378	-0.110126	0.148431	9.877821	0.011591	-0.015188	0.126303
+3.580359	-0.105338	0.450080	9.858669	0.012124	-0.028378	0.140959
+3.581412	0.000000	0.797216	9.600112	0.009726	-0.050228	0.162942
+3.582410	0.416563	1.165899	9.425347	0.009859	-0.080072	0.192919
+3.583411	0.564994	1.659072	9.494774	0.023182	-0.140959	0.256870
+3.584442	0.608087	3.255898	9.262552	0.043433	-0.268861	0.374247
+3.585422	1.405303	5.700216	8.359998	-0.005729	-0.286580	0.404890
+3.586442	0.301649	2.293493	7.680090	-0.098191	-0.126836	0.241415
+3.587442	-0.330378	-1.831443	9.375072	-0.057423	-0.043167	0.095127
+3.588440	-0.155613	-0.708637	12.954167	0.078740	-0.083536	0.033708
+3.589508	-0.859461	2.078029	10.754041	0.127236	-0.137495	0.037704
+3.590509	-0.514719	2.324616	8.087077	0.111648	-0.170003	0.050894
+3.591508	-0.296861	3.555154	8.450972	0.189322	-0.320688	0.025181
+3.592509	0.047881	7.399987	7.974557	0.386104	-0.710256	0.098991
+3.593510	6.066505	8.436607	0.588935	1.015355	-1.414250	0.496953
+3.594508	-2.276735	6.928360	-8.122988	0.509210	-1.239717	0.952337
+3.595498	-16.193307	-8.972873	8.537157	-0.312028	-0.921427	0.894648
+3.596434	-4.898212	-13.928542	19.181072	-0.130433	-1.293942	0.712387
+3.597434	4.546288	-3.160137	13.945300	0.193452	-1.629551	0.488825
+3.598437	0.280103	2.386861	2.267159	0.127769	-1.333645	0.531193
+3.599434	-4.486437	8.151716	-2.777090	-0.444726	-0.124038	0.867602
+3.600433	0.921707	8.419849	-33.612363	-1.333112	2.166340	1.114346
+3.601429	-0.940859	-18.934486	-36.379877	-1.766779	2.432270	0.968591
+3.602437	-15.575644	-18.369492	26.356019	-1.390801	1.304600	0.867868
+3.603435	6.873297	-20.873661	5.884558	-1.124605	0.980182	0.629251
+3.604421	9.688692	4.692324	4.816814	-0.478433	0.790194	0.033841
+3.605419	13.902208	11.003021	24.957898	-0.112580	0.166139	0.173067
+3.606414	2.300675	-1.197021	23.231793	-0.238617	-0.136029	0.291243
+3.607421	-4.165635	8.168475	20.950270	-0.162142	-0.061153	0.187590
+3.608412	-1.718923	0.895372	27.667955	0.281384	0.071678	-0.115778
+3.609422	5.898922	-16.533261	27.634438	0.646571	0.095127	-0.324685
+3.610506	-1.137170	-7.680090	12.482540	-0.083270	0.588882	-0.226227
+3.611508	1.158717	6.933148	6.183813	-1.281152	1.228925	0.133631
+3.612453	-4.701900	17.668037	5.185497	-1.587317	1.081305	0.376911
+3.613387	-2.609507	6.679380	8.190021	-1.031609	1.149119	0.261266
+3.614386	7.232404	-12.326927	6.997788	-0.604204	1.704694	-0.054625
+3.615385	9.260158	-16.535655	5.961167	-0.491623	2.124505	-0.273790
+3.616389	-0.897766	8.551521	12.106675	-0.679346	1.780902	-0.073144
+3.617347	-8.484488	7.555600	15.250054	-0.650835	1.538554	0.004397
+3.618380	2.329404	-10.672644	11.668565	-0.507611	1.576792	-0.117243
+3.619414	2.496987	-2.370103	22.621312	-0.451654	0.680412	-0.133364
+3.620416	-9.066241	8.125382	33.959500	-0.224628	-0.019851	-0.024781
+3.621449	-4.225486	-3.035646	13.842356	0.009459	-0.018652	0.063152
+3.622449	0.505143	-3.224776	14.144006	0.113380	0.170403	0.048363
+3.623444	1.156323	-0.754124	10.256080	0.054492	0.251807	-0.000133
+3.624409	0.184341	0.847491	7.285073	-0.004796	0.264464	-0.008127
+3.625390	-0.485991	-0.380653	9.020754	0.021184	0.276455	0.003331
+3.626449	-0.311226	-1.170687	10.562518	0.109916	0.317757	0.010126
+3.627443	-0.045487	-1.307147	10.445209	0.236086	0.421011	0.009859
+3.628448	0.572176	-1.271237	9.442105	0.382240	0.608600	0.012657
+3.629377	0.981558	-1.364604	8.709528	0.487093	0.760084	0.012524
+3.630370	0.421352	-1.800320	10.464362	0.477234	0.603671	-0.005329
+3.631347	-1.608797	-2.537686	10.818680	0.510409	0.150951	-0.022516
+3.632346	-2.604719	-2.463470	5.025096	0.650035	-0.143090	-0.013323
+3.633344	-1.448396	-0.227434	2.880034	0.751557	-0.167472	-0.005462
+3.634353	-0.763700	0.667938	8.802896	0.621657	-0.044766	-0.021583
+3.635366	-0.131672	1.529793	15.276388	0.342138	0.074476	-0.029577
+3.636401	0.153219	1.153929	14.797580	0.179729	0.106185	-0.031043
+3.637448	-0.272921	0.167583	10.593640	0.161077	0.080871	-0.028378
+3.638448	-0.734971	0.045487	8.515611	0.217700	0.039303	-0.022383
+3.639449	-0.766094	-0.600905	8.443790	0.298172	0.006528	-0.022250
+3.640444	-0.500355	-1.000710	8.544339	0.399161	-0.025181	-0.021850
+3.641430	-0.538660	-0.991134	7.945829	0.498152	-0.053026	-0.014522
+3.642440	-0.416563	-0.141249	8.264236	0.435266	-0.003331	-0.007194
+3.643380	0.107732	1.434032	12.099493	0.202778	0.072478	-0.007461
+3.644382	0.062245	0.562600	14.347500	0.066482	0.106985	-0.016654
+3.645386	-0.031123	-0.749335	11.647019	0.067015	0.111115	-0.022250
+3.646360	-0.402199	-0.265739	9.628841	0.099124	0.098325	-0.022516
+3.647360	-0.507537	-0.105338	9.422953	0.108850	0.087799	-0.021317
+3.648353	-0.368683	-0.248980	9.956825	0.095127	0.086600	-0.019985
+3.649509	-0.373471	-0.246586	10.505061	0.068747	0.089132	-0.019718
+3.650508	-0.445292	-0.184341	10.464362	0.046364	0.089265	-0.020917
+3.651470	-0.440504	-0.229828	10.215381	0.033308	0.086867	-0.020518
+3.652509	-0.435716	-0.280103	10.054980	0.027179	0.083669	-0.021850
+3.653460	-0.464444	-0.292073	9.966401	0.025580	0.083270	-0.019985
+3.654468	-0.418958	-0.375865	10.038222	0.026779	0.080871	-0.018919
+3.655506	-0.438110	-0.339954	10.098073	0.025580	0.074743	-0.020518
+3.656507	-0.416563	-0.304043	9.892186	0.020784	0.067415	-0.019985
+3.657511	-0.426140	-0.337560	9.911338	0.018119	0.061819	-0.020651
+3.658509	-0.459656	-0.378259	10.040616	0.015988	0.055158	-0.020518
+3.659508	-0.445292	-0.392623	9.973583	0.014655	0.049296	-0.020651
+3.660507	-0.399805	-0.416563	9.987947	0.016254	0.047164	-0.021450
+3.661510	-0.411775	-0.409381	10.054980	0.019052	0.045832	-0.022250
+3.662435	-0.387835	-0.390229	9.983159	0.021717	0.044766	-0.020651
+3.663422	-0.440504	-0.316014	9.942460	0.022516	0.043433	-0.020784
+3.664412	-0.402199	-0.409381	9.928096	0.021983	0.042101	-0.023315
+3.665416	-0.402199	-0.397411	9.911338	0.022783	0.039969	-0.023582
+3.666409	-0.442898	-0.368683	9.954431	0.023049	0.036639	-0.023182
+3.667413	-0.476415	-0.359106	9.906550	0.024115	0.033974	-0.023315
+3.668413	-0.454868	-0.344742	9.863457	0.023049	0.032508	-0.022916
+3.669415	-0.416563	-0.301649	9.791636	0.023182	0.030510	-0.020118
+3.670412	-0.462050	-0.318408	9.837123	0.024515	0.028245	-0.019452
+3.671460	-0.464444	-0.325590	9.865851	0.025714	0.027845	-0.021583
+3.672509	-0.440504	-0.330378	9.748543	0.026247	0.026646	-0.021317
+3.673466	-0.433322	-0.316014	9.825152	0.025847	0.025847	-0.018919
+3.674508	-0.433322	-0.294467	9.777271	0.026380	0.025847	-0.017720
+3.675513	-0.442898	-0.356712	9.896974	0.028378	0.027046	-0.018919
+3.676507	-0.354318	-0.404593	9.865851	0.029311	0.026646	-0.019319
+3.677510	-0.359106	-0.337560	9.817970	0.030243	0.026646	-0.017587
+3.678509	-0.392623	-0.263345	9.868245	0.030110	0.026247	-0.017320
+3.679511	-0.423746	-0.327984	9.770089	0.030910	0.027312	-0.019718
+3.680424	-0.395017	-0.368683	9.789242	0.032109	0.028112	-0.020251
+3.681389	-0.454868	-0.325590	9.801212	0.032242	0.029444	-0.020917
+3.682389	-0.406987	-0.397411	9.760513	0.035306	0.029977	-0.018786
+3.683383	-0.363895	-0.356712	9.736573	0.035839	0.030377	-0.018386
+3.684387	-0.411775	-0.277709	9.676722	0.035839	0.031043	-0.019052
+3.685374	-0.359106	-0.306437	9.719814	0.036106	0.031043	-0.019718
+3.686490	-0.337560	-0.395017	9.738967	0.036372	0.031709	-0.016521
+3.687386	-0.390229	-0.347136	9.667146	0.036905	0.032375	-0.018253
+3.688411	-0.404593	-0.304043	9.621659	0.036772	0.033574	-0.019185
+3.689409	-0.416563	-0.318408	9.674328	0.035972	0.035440	-0.019452
+3.690459	-0.385441	-0.313620	9.712632	0.037172	0.037438	-0.019985
+3.691423	-0.383047	-0.327984	9.671934	0.038904	0.039170	-0.019585
+3.692443	-0.349530	-0.301649	9.698268	0.037971	0.039303	-0.019185
+3.693438	-0.330378	-0.332772	9.647993	0.037571	0.039037	-0.020118
+3.694454	-0.359106	-0.131672	9.540261	0.030110	0.039570	-0.021850
+3.695496	-0.275315	-0.100550	9.308039	0.025447	0.040103	-0.023449
+3.696393	-0.351924	-0.383047	9.920914	0.031309	0.041168	-0.022250
+3.697389	-0.308832	-0.524295	10.021464	0.038237	0.043700	-0.020917
+3.698387	-0.327984	-0.325590	9.760513	0.038770	0.044499	-0.023449
+3.699389	-0.270527	-0.213070	9.616871	0.035173	0.046098	-0.023582
+3.700386	-0.287285	-0.268133	9.597718	0.033708	0.048096	-0.023715
+3.701356	-0.335166	-0.316014	9.719814	0.033574	0.047963	-0.023982
+3.702445	-0.347136	-0.292073	9.779666	0.031043	0.048230	-0.024781
+3.703445	-0.356712	-0.246586	9.626447	0.028378	0.049162	-0.025047
+3.704394	-0.304043	-0.244192	9.542655	0.025847	0.050361	-0.026380
+3.705417	-0.304043	-0.201100	9.523503	0.021583	0.051960	-0.027579
+3.706470	-0.304043	-0.208282	9.523503	0.016387	0.053959	-0.025580
+3.707448	-0.301649	-0.229828	9.542655	0.013190	0.055424	-0.024648
+3.708401	-0.323196	-0.213070	9.549837	0.008127	0.055824	-0.025447
+3.709398	-0.351924	-0.256163	9.518715	0.004663	0.055291	-0.026113
+3.710403	-0.361500	-0.268133	9.521109	0.001599	0.057156	-0.026247
+3.711397	-0.363895	-0.210676	9.530685	-0.001066	0.058089	-0.025181
+3.712448	-0.327984	-0.215464	9.568990	-0.002665	0.059021	-0.025181
+3.713379	-0.311226	-0.284891	9.552231	-0.005596	0.061153	-0.025447
+3.714349	-0.313620	-0.256163	9.597718	-0.009726	0.062086	-0.026779
+3.715343	-0.304043	-0.201100	9.578566	-0.012923	0.062885	-0.028645
+3.716423	-0.272921	-0.251375	9.509139	-0.016387	0.064084	-0.029577
+3.717405	-0.308832	-0.241798	9.537867	-0.020651	0.067282	-0.028511
+3.718414	-0.330378	-0.217858	9.573778	-0.025181	0.069147	-0.028378
+3.719444	-0.320802	-0.256163	9.683904	-0.024914	0.068614	-0.029711
+3.720404	-0.361500	-0.289679	9.674328	-0.025847	0.067548	-0.031309
+3.721452	-0.359106	-0.263345	9.750937	-0.029044	0.069547	-0.030910
+3.722449	-0.296861	-0.339954	9.806000	-0.031043	0.071012	-0.028511
+3.723449	-0.344742	-0.397411	9.961613	-0.027579	0.072078	-0.027712
+3.724447	-0.347136	-0.368683	9.846699	-0.024914	0.074210	-0.030510
+3.725448	-0.296861	-0.325590	9.717420	-0.024381	0.077807	-0.032642
+3.726436	-0.287285	-0.244192	9.592930	-0.028511	0.079672	-0.031309
+3.727442	-0.287285	-0.198706	9.434923	-0.035440	0.077807	-0.033041
+3.728450	-0.392623	-0.280103	9.731785	-0.035040	0.075542	-0.034374
+3.729378	-0.457262	-0.299255	9.614477	-0.033441	0.076874	-0.032775
+3.730345	-0.325590	-0.004788	9.205095	-0.040236	0.080205	-0.035173
+3.731354	-0.272921	0.038305	9.169185	-0.047164	0.082470	-0.037838
+3.732389	-0.234616	-0.256163	9.257764	-0.019319	0.063018	-0.037305
+3.733390	-0.706243	-1.417273	7.505325	0.209972	-0.030776	-0.035040
+3.734398	-1.029438	-2.640629	5.362656	0.342404	-0.042767	-0.025714
+3.735371	-0.564994	0.852279	11.465072	0.227292	0.007461	-0.019851
+3.736397	0.198706	0.198706	12.468176	0.087666	0.057156	-0.029844
+3.737371	0.241798	-0.083792	10.974293	0.024248	0.062485	-0.042767
+3.738371	-0.514719	-0.117308	10.931200	0.011058	0.050361	-0.041835
+3.739366	-0.476415	-0.122096	10.428451	0.000533	0.052626	-0.036639
+3.740367	-0.277709	-0.258557	10.402117	-0.015322	0.063285	-0.035706
+3.741394	-0.232222	-0.390229	10.466756	-0.025314	0.073410	-0.036505
+3.742392	-0.172371	-0.045487	9.655175	-0.037038	0.073011	-0.040502
+3.743395	-0.287285	0.160401	8.908234	-0.054225	0.071145	-0.041835
+3.744396	-0.536266	-0.553024	10.311143	-0.041835	0.067948	-0.040769
+3.745396	-0.385441	-0.033517	9.552231	-0.045165	0.066882	-0.044100
+3.746336	-0.193917	0.646392	7.586722	-0.075675	0.065417	-0.047430
+3.747330	-0.428534	-0.519507	9.877821	-0.060753	0.053292	-0.047164
+3.748339	-0.409381	-1.304753	10.782770	0.019851	0.012790	-0.046764
+3.749391	-0.866644	-1.374181	9.138062	0.143090	-0.062752	-0.048096
+3.750396	-1.225750	-1.122806	8.130170	0.245678	-0.128568	-0.048096
+3.751396	-0.943253	-0.864250	8.290571	0.255005	-0.279786	-0.047963
+3.752395	-0.739759	-2.063665	8.886687	0.219965	-0.484162	-0.062619
+3.753396	-0.679908	1.781168	8.786138	0.068747	-0.262998	-0.055424
+3.754401	0.902554	2.568808	10.787558	-0.066349	0.022783	-0.043167
+3.755371	0.737365	-0.505143	12.851223	-0.079139	0.121907	-0.044100
+3.756367	-0.004788	-0.900160	11.398039	-0.041835	0.101256	-0.043700
+3.757367	-0.517113	-0.603299	10.622369	-0.016387	0.063418	-0.041968
+3.758378	-0.304043	-0.395017	10.074133	-0.014922	0.053159	-0.041568
+3.759392	-0.373471	-0.277709	9.815576	-0.025847	0.057423	-0.042501
+3.760396	-0.366289	-0.335166	9.798818	-0.031576	0.061286	-0.042634
+3.761400	-0.378259	-0.452474	10.026252	-0.028112	0.062619	-0.041968
+3.762371	-0.366289	-0.409381	9.889792	-0.022916	0.060620	-0.041701
+3.763360	-0.392623	-0.296861	9.820364	-0.022516	0.060887	-0.041968
+3.764359	-0.342348	-0.359106	9.918520	-0.022383	0.060753	-0.042234
+3.765396	-0.330378	-0.330378	9.803606	-0.022516	0.061553	-0.041035
+3.766512	-0.435716	-0.332772	9.705450	-0.023982	0.061020	-0.041701
+3.767508	-0.469232	-0.327984	9.755725	-0.023982	0.058489	-0.041568
+3.768462	-0.464444	-0.351924	9.908944	-0.021583	0.057556	-0.038637
+3.769464	-0.409381	-0.366289	9.841911	-0.020518	0.058089	-0.037438
+3.770508	-0.371077	-0.289679	9.767695	-0.020651	0.059554	-0.040369
+3.771446	-0.304043	-0.356712	9.748543	-0.019452	0.060887	-0.040636
+3.772473	-0.330378	-0.371077	9.798818	-0.018386	0.061553	-0.040902
+3.773509	-0.368683	-0.337560	9.710238	-0.018386	0.064084	-0.040502
+3.774508	-0.371077	-0.356712	9.652781	-0.017320	0.066882	-0.040902
+3.775508	-0.378259	-0.354318	9.710238	-0.016787	0.068614	-0.041568
+3.776473	-0.351924	-0.363895	9.794030	-0.016654	0.069547	-0.040902
+3.777465	-0.392623	-0.359106	9.765301	-0.015988	0.069813	-0.040236
+3.778505	-0.397411	-0.342348	9.746149	-0.014522	0.069680	-0.040369
+3.779505	-0.387835	-0.366289	9.774877	-0.014123	0.071279	-0.041568
+3.780423	-0.375865	-0.423746	9.762907	-0.013989	0.072211	-0.039969
+3.781415	-0.378259	-0.395017	9.777271	-0.012391	0.072478	-0.038770
+3.782411	-0.404593	-0.378259	9.794030	-0.010792	0.072078	-0.039037
+3.783409	-0.418958	-0.339954	9.825152	-0.010792	0.071545	-0.037704
+3.784413	-0.433322	-0.335166	9.794030	-0.011458	0.072744	-0.036772
+3.785344	-0.368683	-0.272921	9.846699	-0.011724	0.075675	-0.035040
+3.786358	-0.387835	-0.354318	9.827546	-0.010392	0.076741	-0.036106
+3.787351	-0.383047	-0.375865	9.794030	-0.007061	0.077141	-0.035972
+3.788354	-0.414169	-0.375865	9.870639	-0.005063	0.076741	-0.035173
+3.789355	-0.375865	-0.323196	9.734179	-0.005729	0.076874	-0.035573
+3.790355	-0.335166	-0.366289	9.779666	-0.004930	0.078606	-0.033708
+3.791354	-0.378259	-0.284891	9.719814	-0.004530	0.081937	-0.033841
+3.792350	-0.385441	-0.203494	9.394225	-0.007727	0.083136	-0.034773
+3.793355	-0.359106	-0.131672	9.236218	-0.013323	0.082870	-0.036505
+3.794355	-0.337560	-0.323196	9.568990	-0.010925	0.079806	-0.037838
+3.795350	-0.354318	-0.481203	9.774877	0.003597	0.070879	-0.036772
+3.796355	-0.476415	-0.512325	9.537867	0.035839	0.046098	-0.036505
+3.797416	-0.574570	-0.541054	9.245794	0.050361	0.039703	-0.034773
+3.798412	-0.337560	-0.143643	9.645599	0.026513	0.059155	-0.033441
+3.799411	-0.184341	-0.093368	9.987947	-0.002665	0.078340	-0.034773
+3.800397	-0.244192	-0.167583	9.992735	-0.018119	0.084469	-0.035040
+3.801467	-0.371077	-0.203494	9.801212	-0.022783	0.082204	-0.035040
+3.802506	-0.392623	-0.222646	9.741361	-0.023715	0.078340	-0.035306
+3.803509	-0.344742	-0.270527	9.710238	-0.025847	0.075809	-0.036106
+3.804508	-0.387835	-0.284891	9.753331	-0.027979	0.074077	-0.035573
+3.805507	-0.440504	-0.313620	9.868245	-0.030110	0.072877	-0.036639
+3.806502	-0.402199	-0.361500	9.858669	-0.031842	0.069946	-0.034773
+3.807506	-0.406987	-0.363895	9.794030	-0.031576	0.068614	-0.034374
+3.808506	-0.421352	-0.330378	9.849093	-0.028778	0.067548	-0.033441
+3.809462	-0.373471	-0.335166	9.944854	-0.026513	0.067415	-0.033175
+3.810499	-0.409381	-0.327984	9.889792	-0.023049	0.066482	-0.031309
+3.811509	-0.390229	-0.385441	9.825152	-0.022250	0.065417	-0.028645
+3.812506	-0.368683	-0.383047	9.815576	-0.021983	0.064750	-0.029711
+3.813423	-0.378259	-0.368683	9.861063	-0.019851	0.063152	-0.029577
+3.814417	-0.383047	-0.433322	9.940066	-0.017986	0.064351	-0.029444
+3.815408	-0.366289	-0.450080	9.863457	-0.016787	0.064484	-0.029977
+3.816413	-0.416563	-0.483597	9.877821	-0.013989	0.064617	-0.027845
+3.817398	-0.418958	-0.428534	9.880215	-0.013323	0.064617	-0.026247
+3.818391	-0.397411	-0.404593	9.762907	-0.012391	0.064217	-0.025447
+3.819397	-0.395017	-0.526689	9.904156	-0.009459	0.064084	-0.025447
+3.820365	-0.497961	-0.351924	9.813182	-0.009459	0.058755	-0.026779
+3.821340	-0.459656	0.016758	9.061453	-0.021450	0.055824	-0.027579
+3.822336	-0.330378	-0.301649	9.415771	-0.026646	0.055025	-0.029711
+3.823388	-0.280103	-0.588935	10.031040	-0.020518	0.057023	-0.029844
+3.824386	-0.371077	-0.553024	10.043010	-0.011191	0.057156	-0.026380
+3.825387	-0.363895	-0.476415	9.949643	-0.006129	0.056090	-0.024914
+3.826386	-0.433322	-0.411775	9.832334	-0.005196	0.054758	-0.026646
+3.827386	-0.428534	-0.378259	9.906550	-0.005729	0.052760	-0.027979
+3.828421	-0.409381	-0.416563	9.964007	-0.005063	0.050894	-0.025847
+3.829477	-0.402199	-0.359106	9.861063	-0.005196	0.049429	-0.024914
+3.830399	-0.390229	-0.395017	9.839517	-0.003730	0.049029	-0.023848
+3.831409	-0.387835	-0.390229	9.873033	-0.002265	0.048230	-0.025580
+3.832376	-0.392623	-0.423746	9.777271	-0.001199	0.048363	-0.026113
+3.833374	-0.351924	-0.409381	9.755725	-0.001998	0.047164	-0.025047
+3.834405	-0.383047	-0.452474	9.736573	-0.001332	0.046897	-0.025047
+3.835421	-0.430928	-0.457262	9.782060	0.000133	0.046231	-0.026113
+3.836426	-0.438110	-0.323196	9.659963	-0.001732	0.046631	-0.026247
+3.837414	-0.457262	-0.363895	9.619265	-0.002931	0.047697	-0.026913
+3.838423	-0.438110	-0.363895	9.794030	-0.003331	0.047297	-0.023982
+3.839418	-0.435716	-0.418958	9.870639	-0.001466	0.047297	-0.021850
+3.840477	-0.462050	-0.387835	9.777271	-0.000933	0.045965	-0.020251
+3.841452	-0.433322	-0.330378	9.576172	-0.002398	0.044766	-0.021583
+3.842431	-0.373471	-0.296861	9.600112	-0.006662	0.045299	-0.020917
+3.843456	-0.368683	-0.234616	9.585748	-0.013057	0.045565	-0.020784
+3.844424	-0.337560	-0.263345	9.576172	-0.015055	0.044899	-0.020518
+3.845410	-0.474021	-0.433322	9.755725	-0.013190	0.044899	-0.020118
+3.846388	-0.387835	-0.378259	9.686298	-0.012923	0.043034	-0.019052
+3.847382	-0.383047	-0.404593	9.774877	-0.010925	0.042101	-0.019985
+3.848402	-0.442898	-0.409381	9.794030	-0.007994	0.039037	-0.021850
+3.849399	-0.464444	-0.325590	9.554625	-0.007061	0.033974	-0.021184
+3.850393	-0.435716	-0.385441	9.492380	-0.001199	0.021983	-0.021450
+3.851417	-0.572176	-0.598511	9.619265	0.024115	-0.009326	-0.022116
+3.852479	-0.670332	-0.581752	9.111728	0.055824	-0.050628	-0.020651
+3.853480	-0.643998	-0.452474	9.530685	0.054492	-0.046231	-0.017187
+3.854450	-0.203494	-0.215464	10.052586	0.026113	-0.007594	-0.019052
+3.855433	-0.055063	-0.256163	10.014282	0.000400	0.022250	-0.021983
+3.856483	-0.126884	-0.284891	9.942460	-0.011724	0.032508	-0.022250
+3.857483	-0.313620	-0.330378	9.741361	-0.014922	0.032642	-0.023449
+3.858480	-0.409381	-0.404593	9.853881	-0.016521	0.030377	-0.023315
+3.859481	-0.380653	-0.292073	9.746149	-0.020118	0.026513	-0.023715
+3.860479	-0.397411	-0.304043	9.588142	-0.031043	0.008793	-0.024381
+3.861479	-0.423746	-0.818763	9.681510	-0.037038	-0.055424	-0.021850
+3.862425	-0.888190	-0.883402	9.154820	0.006662	-0.162276	-0.019185
+3.863401	-1.271237	-1.874536	7.306619	0.083536	-0.605003	0.023715
+3.864397	-5.740915	-9.863457	-0.153219	0.432735	-2.021118	0.201845
+3.865379	-11.611108	-0.672726	4.567834	0.267262	-1.897213	0.215168
+3.866397	9.779666	19.152344	7.639391	-0.242614	-0.562769	0.076608
+3.867388	8.470124	-3.131408	19.291198	-0.310695	0.098058	-0.078473
+3.868480	-0.110126	-4.519953	15.992207	-0.109916	0.064484	-0.095793
+3.869427	-2.092394	-0.754124	12.077947	0.010925	-0.053026	-0.031842
+3.870422	0.454868	-0.095762	10.457180	0.003198	-0.051560	-0.008527
+3.871408	0.646392	-0.476415	10.416481	-0.030510	0.010925	-0.018119
+3.872420	-0.359106	-0.404593	10.155530	-0.050228	0.045299	-0.028245
+3.873418	-0.021546	-0.660756	10.272838	-0.040769	0.048496	-0.032908
+3.874480	-0.095762	-0.679908	10.265656	-0.022916	0.042234	-0.031842
+3.875429	-0.325590	-0.280103	9.681510	-0.024515	0.039436	-0.027579
+3.876439	-0.416563	-0.438110	9.935278	-0.028245	0.037838	-0.025714
+3.877484	-0.186735	-0.493173	10.043010	-0.024248	0.041302	-0.028645
+3.878477	-0.069427	-0.239404	9.501957	-0.026913	0.046098	-0.031709
+3.879479	-0.380653	-0.304043	9.609688	-0.031975	0.045965	-0.028511
+3.880402	-0.471626	-0.450080	9.932884	-0.030910	0.041035	-0.025181
+3.881382	-0.373471	-0.411775	9.695874	-0.030643	0.037438	-0.022783
+3.882400	-0.342348	-0.201100	9.470834	-0.039303	0.035040	-0.021184
+3.883400	-0.227434	-0.361500	9.738967	-0.043300	0.032508	-0.022250
+3.884394	-0.160401	-0.481203	9.882609	-0.037971	0.031975	-0.021983
+3.885425	-0.284891	-0.416563	9.636023	-0.035706	0.028645	-0.020118
+3.886369	-0.361500	-0.383047	9.662357	-0.035173	0.022383	-0.019585
+3.887400	-0.349530	-0.560206	9.952037	-0.020784	0.000799	-0.021583
+3.888473	-0.426140	-1.297571	10.727707	0.021850	-0.051427	-0.025847
+3.889483	-0.277709	-1.098866	8.568280	0.066083	-0.169737	-0.026513
+3.890479	-1.106048	-0.452474	7.675302	0.094594	-0.295507	-0.023449
+3.891481	-0.790034	-0.682302	8.283389	0.150818	-0.428605	-0.027845
+3.892486	-0.878614	-2.030148	8.324087	0.240616	-0.674283	-0.042234
+3.893478	-1.015074	-2.568808	8.178051	0.245812	-0.935816	-0.056357
+3.894480	-0.778064	-0.684696	8.084683	0.096992	-0.921161	-0.045965
+3.895440	0.519507	5.503905	9.590536	-0.145222	-0.360790	-0.015855
+3.896406	2.022966	3.382783	10.952747	-0.225427	0.058355	-0.010259
+3.897406	0.119702	-3.495303	16.152608	-0.078740	0.114579	-0.022116
+3.898398	0.909736	-2.070847	12.827282	0.038504	0.059021	-0.029844
+3.899399	-0.397411	-0.165189	9.796424	0.052760	0.018519	-0.026380
+3.900399	-0.177159	-0.459656	9.973583	0.032109	0.023449	-0.021184
+3.901479	-0.126884	-0.409381	9.961613	0.017320	0.036639	-0.019052
+3.902477	-0.222646	-0.402199	9.837123	0.014256	0.041568	-0.020518
+3.903478	-0.205888	-0.366289	9.837123	0.018652	0.041701	-0.021583
+3.904474	-0.201100	-0.380653	9.868245	0.021850	0.040636	-0.022383
+3.905479	-0.193917	-0.428534	9.935278	0.023049	0.043966	-0.022250
+3.906424	-0.189129	-0.411775	9.853881	0.023582	0.045432	-0.022649
+3.907475	-0.162795	-0.423746	9.738967	0.022116	0.045165	-0.022783
+3.908474	-0.225040	-0.409381	9.772483	0.019452	0.039303	-0.020917
+3.909481	-0.277709	-0.380653	9.717420	0.017720	0.036505	-0.018919
+3.910479	-0.136460	-0.390229	9.839517	0.018519	0.037438	-0.017853
+3.911478	-0.208282	-0.390229	9.827546	0.018919	0.037438	-0.019185
+3.912476	-0.208282	-0.397411	9.782060	0.019052	0.036772	-0.019718
+3.913418	-0.141249	-0.459656	9.736573	0.018652	0.037704	-0.017853
+3.914386	-0.141249	-0.433322	9.707844	0.018786	0.038371	-0.018786
+3.915399	-0.193917	-0.430928	9.712632	0.020118	0.039570	-0.018786
+3.916393	-0.184341	-0.397411	9.734179	0.021717	0.041435	-0.017187
+3.917400	-0.193917	-0.387835	9.770089	0.022116	0.042368	-0.014655
+3.918385	-0.246586	-0.442898	9.774877	0.021317	0.040369	-0.014922
+3.919419	-0.241798	-0.466838	9.813182	0.020251	0.041168	-0.015455
+3.920418	-0.256163	-0.435716	9.825152	0.021051	0.043433	-0.014789
+3.921481	-0.241798	-0.416563	9.782060	0.021583	0.044499	-0.013723
+3.922480	-0.136460	-0.406987	9.806000	0.021717	0.044899	-0.011991
+3.923478	-0.177159	-0.380653	9.813182	0.021184	0.043833	-0.010792
+3.924479	-0.227434	-0.385441	9.770089	0.020518	0.043300	-0.012391
+3.925479	-0.237010	-0.373471	9.822758	0.019319	0.041568	-0.010525
+3.926449	-0.186735	-0.404593	9.782060	0.019851	0.042634	-0.009726
+3.927418	-0.150825	-0.387835	9.853881	0.020251	0.043966	-0.011325
+3.928473	-0.146037	-0.430928	9.839517	0.021317	0.044366	-0.011858
+3.929401	-0.146037	-0.430928	9.813182	0.021983	0.044233	-0.011858
+3.930399	-0.220252	-0.397411	9.863457	0.021450	0.045299	-0.011991
+3.931383	-0.198706	-0.402199	9.784454	0.021051	0.044899	-0.012524
+3.932399	-0.093368	-0.411775	9.715026	0.020784	0.044100	-0.013190
+3.933401	-0.129278	-0.421352	9.655175	0.020384	0.043833	-0.013590
+3.934373	-0.155613	-0.399805	9.738967	0.021317	0.044100	-0.013989
+3.935356	-0.169977	-0.392623	9.717420	0.020784	0.046764	-0.012391
+3.936367	-0.256163	-0.411775	9.722208	0.020118	0.047031	-0.010525
+3.937401	-0.237010	-0.414169	9.779666	0.019185	0.045165	-0.010525
+3.938397	-0.210676	-0.450080	9.784454	0.019585	0.042767	-0.011724
+3.939396	-0.213070	-0.438110	9.758119	0.019718	0.041701	-0.012257
+3.940399	-0.162795	-0.426140	9.750937	0.019052	0.041168	-0.011858
+3.941371	-0.160401	-0.387835	9.750937	0.017720	0.041701	-0.011591
+3.942368	-0.196312	-0.466838	9.794030	0.019585	0.042368	-0.012257
+3.943360	-0.213070	-0.445292	9.817970	0.019185	0.043300	-0.012657
+3.944369	-0.160401	-0.440504	9.851487	0.018919	0.042900	-0.013590
+3.945366	-0.201100	-0.399805	9.782060	0.019718	0.041701	-0.014655
+3.946361	-0.177159	-0.416563	9.729391	0.019985	0.040236	-0.014256
+3.947360	-0.208282	-0.474021	9.741361	0.018786	0.040902	-0.014123
+3.948365	-0.095762	-0.445292	9.734179	0.019585	0.041568	-0.014389
+3.949364	-0.136460	-0.442898	9.741361	0.019985	0.042368	-0.013590
+3.950365	-0.167583	-0.418958	9.803606	0.019585	0.042767	-0.014123
+3.951365	-0.155613	-0.320802	9.801212	0.019319	0.041701	-0.014922
+3.952365	-0.112520	-0.380653	9.693480	0.018919	0.040103	-0.015455
+3.953365	-0.119702	-0.402199	9.758119	0.018519	0.041035	-0.015588
+3.954364	-0.117308	-0.423746	9.858669	0.017853	0.042900	-0.016521
+3.955403	-0.117308	-0.416563	9.789242	0.019052	0.043567	-0.015988
+3.956369	-0.184341	-0.368683	9.746149	0.021184	0.044100	-0.016521
+3.957370	-0.220252	-0.363895	9.789242	0.020784	0.042501	-0.014789
+3.958369	-0.184341	-0.450080	9.784454	0.020518	0.042900	-0.013590
+3.959368	-0.090974	-0.411775	9.731785	0.019718	0.043966	-0.014922
+3.960368	-0.141249	-0.395017	9.724603	0.021317	0.044233	-0.015455
+3.961369	-0.146037	-0.426140	9.726997	0.021184	0.043700	-0.016387
+3.962372	-0.172371	-0.406987	9.760513	0.020651	0.043833	-0.015588
+3.963369	-0.244192	-0.373471	9.722208	0.020784	0.045299	-0.015455
+3.964370	-0.201100	-0.356712	9.715026	0.022250	0.044766	-0.015988
+3.965369	-0.184341	-0.392623	9.810788	0.022516	0.043433	-0.016521
+3.966381	-0.165189	-0.385441	9.851487	0.022383	0.044366	-0.016387
+3.967369	-0.138854	-0.373471	9.750937	0.022116	0.045165	-0.017187
+3.968369	-0.129278	-0.392623	9.738967	0.021051	0.043700	-0.018919
+3.969377	-0.155613	-0.349530	9.762907	0.021184	0.045032	-0.019718
+3.970380	-0.146037	-0.306437	9.729391	0.020917	0.046098	-0.018253
+3.971370	-0.093368	-0.327984	9.774877	0.021051	0.044366	-0.017054
+3.972343	-0.110126	-0.409381	9.803606	0.022116	0.044233	-0.015855
+3.973369	-0.141249	-0.466838	9.794030	0.021583	0.045832	-0.016787
+3.974369	-0.129278	-0.395017	9.765301	0.021450	0.046498	-0.014922
+3.975369	-0.155613	-0.445292	9.806000	0.020518	0.047697	-0.015188
+3.976369	-0.107732	-0.457262	9.772483	0.021051	0.046897	-0.017720
+3.977369	-0.153219	-0.416563	9.779666	0.021583	0.046098	-0.016121
+3.978369	-0.143643	-0.399805	9.683904	0.022116	0.046498	-0.014789
+3.979371	-0.169977	-0.385441	9.681510	0.020651	0.047164	-0.014789
+3.980369	-0.153219	-0.373471	9.717420	0.020518	0.047963	-0.017453
+3.981369	-0.122096	-0.349530	9.791636	0.021317	0.047297	-0.018652
+3.982369	-0.148431	-0.406987	9.813182	0.022250	0.046098	-0.016121
+3.983369	-0.141249	-0.380653	9.767695	0.022383	0.046897	-0.012657
+3.984383	-0.100550	-0.380653	9.760513	0.021717	0.047963	-0.012790
+3.985370	-0.165189	-0.392623	9.789242	0.021850	0.047297	-0.014655
+3.986369	-0.169977	-0.423746	9.746149	0.022250	0.046231	-0.016521
+3.987369	-0.107732	-0.442898	9.681510	0.022516	0.045165	-0.016654
+3.988369	-0.155613	-0.435716	9.762907	0.023449	0.045565	-0.014123
+3.989369	-0.203494	-0.457262	9.772483	0.022649	0.046764	-0.013057
+3.990369	-0.217858	-0.430928	9.798818	0.021983	0.047963	-0.011325
+3.991368	-0.126884	-0.395017	9.748543	0.021983	0.048629	-0.011858
+3.992369	-0.143643	-0.416563	9.755725	0.022516	0.048230	-0.012790
+3.993369	-0.172371	-0.402199	9.782060	0.022783	0.047564	-0.013190
+3.994351	-0.167583	-0.368683	9.758119	0.023982	0.048363	-0.014922
+3.995364	-0.189129	-0.368683	9.755725	0.024248	0.049029	-0.015322
+3.996368	-0.141249	-0.337560	9.789242	0.023848	0.048763	-0.014789
+3.997369	-0.148431	-0.383047	9.671934	0.023449	0.046098	-0.013190
+3.998369	-0.126884	-0.426140	9.743755	0.023715	0.045032	-0.014256
+3.999375	-0.141249	-0.445292	9.748543	0.022916	0.044766	-0.013190
+4.000369	-0.134066	-0.421352	9.698268	0.023848	0.044632	-0.011991
+4.001381	-0.143643	-0.366289	9.772483	0.025181	0.043567	-0.014789
+4.002447	-0.205888	-0.392623	9.798818	0.025980	0.042501	-0.015455
+4.003448	-0.229828	-0.430928	9.667146	0.027312	0.041035	-0.015188
+4.004442	-0.277709	-0.466838	9.671934	0.028778	0.037571	-0.014256
+4.005448	-0.239404	-0.440504	9.645599	0.029844	0.032375	-0.013323
+4.006447	-0.220252	-0.418958	9.612083	0.031709	0.027712	-0.013190
+4.007447	-0.222646	-0.440504	9.695874	0.033574	0.025047	-0.014922
+4.008457	-0.220252	-0.423746	9.765301	0.032242	0.027179	-0.015988
+4.009430	-0.162795	-0.440504	9.863457	0.028378	0.035440	-0.014123
+4.010448	-0.093368	-0.368683	9.916126	0.024781	0.041168	-0.015721
+4.011446	-0.098156	-0.404593	9.887397	0.023182	0.043167	-0.016521
+4.012439	-0.131672	-0.433322	9.918520	0.023715	0.044632	-0.016654
+4.013403	-0.172371	-0.390229	9.841911	0.023449	0.046231	-0.015721
+4.014398	-0.186735	-0.423746	9.810788	0.022783	0.049029	-0.014789
+4.015398	-0.203494	-0.416563	9.791636	0.023182	0.049162	-0.016787
+4.016398	-0.169977	-0.383047	9.834729	0.023449	0.048896	-0.016521
+4.017398	-0.143643	-0.399805	9.810788	0.022916	0.048763	-0.016521
+4.018479	-0.119702	-0.351924	9.765301	0.021850	0.048096	-0.015855
+4.019447	-0.146037	-0.385441	9.794030	0.021983	0.048230	-0.015988
+4.020426	-0.119702	-0.383047	9.741361	0.021450	0.047963	-0.015455
+4.021484	-0.162795	-0.356712	9.791636	0.021983	0.049296	-0.015455
+4.022479	-0.153219	-0.454868	9.784454	0.022516	0.049562	-0.013856
+4.023481	-0.148431	-0.438110	9.820364	0.022116	0.048496	-0.015721
+4.024479	-0.186735	-0.445292	9.743755	0.022250	0.047031	-0.016521
+4.025481	-0.179553	-0.435716	9.736573	0.021583	0.048763	-0.015322
+4.026479	-0.167583	-0.447686	9.753331	0.020784	0.049828	-0.015855
+4.027480	-0.136460	-0.409381	9.698268	0.021051	0.049695	-0.016654
+4.028488	-0.134066	-0.409381	9.703056	0.021850	0.048230	-0.016121
+4.029422	-0.208282	-0.423746	9.691086	0.021583	0.048230	-0.013456
+4.030421	-0.184341	-0.368683	9.729391	0.021717	0.049162	-0.011724
+4.031397	-0.162795	-0.378259	9.772483	0.020917	0.047963	-0.011991
+4.032398	-0.177159	-0.385441	9.786848	0.020118	0.048096	-0.011991
+4.033401	-0.136460	-0.392623	9.808394	0.019718	0.048230	-0.013456
+4.034400	-0.155613	-0.375865	9.779666	0.019452	0.046498	-0.014655
+4.035479	-0.196312	-0.380653	9.810788	0.020651	0.047164	-0.015322
+4.036411	-0.186735	-0.397411	9.760513	0.021051	0.047430	-0.014256
+4.037481	-0.174765	-0.421352	9.777271	0.020251	0.047564	-0.015455
+4.038475	-0.112520	-0.395017	9.765301	0.021317	0.047830	-0.015055
+4.039418	-0.098156	-0.383047	9.734179	0.021051	0.048496	-0.013323
+4.040450	-0.122096	-0.426140	9.762907	0.020518	0.047963	-0.014522
+4.041418	-0.165189	-0.428534	9.784454	0.019319	0.048096	-0.015721
+4.042481	-0.155613	-0.442898	9.782060	0.019851	0.048763	-0.015188
+4.043478	-0.129278	-0.406987	9.877821	0.020784	0.049029	-0.013323
+4.044479	-0.155613	-0.404593	9.817970	0.020651	0.049695	-0.014389
+4.045478	-0.153219	-0.368683	9.712632	0.020518	0.048896	-0.014789
+4.046415	-0.172371	-0.359106	9.750937	0.021184	0.047697	-0.015322
+4.047398	-0.201100	-0.344742	9.784454	0.020784	0.047564	-0.015855
+4.048397	-0.167583	-0.356712	9.808394	0.020384	0.048496	-0.016521
+4.049394	-0.110126	-0.411775	9.755725	0.021051	0.048763	-0.015721
+4.050386	-0.114914	-0.404593	9.813182	0.020518	0.048363	-0.015721
+4.051407	-0.162795	-0.380653	9.798818	0.020251	0.048230	-0.014655
+4.052437	-0.174765	-0.418958	9.760513	0.020251	0.048496	-0.015188
+4.053483	-0.167583	-0.430928	9.789242	0.019851	0.049029	-0.016254
+4.054479	-0.162795	-0.385441	9.743755	0.020651	0.048763	-0.015855
+4.055479	-0.112520	-0.421352	9.746149	0.020784	0.048096	-0.015322
+4.056480	-0.107732	-0.404593	9.784454	0.020518	0.048496	-0.016920
+4.057481	-0.110126	-0.363895	9.767695	0.021317	0.048763	-0.015988
+4.058479	-0.131672	-0.375865	9.791636	0.021317	0.047164	-0.016254
+4.059437	-0.213070	-0.390229	9.734179	0.020651	0.046364	-0.016654
+4.060476	-0.153219	-0.409381	9.779666	0.021051	0.046364	-0.015721
+4.061482	-0.083792	-0.332772	9.786848	0.021850	0.046897	-0.015721
+4.062479	-0.131672	-0.344742	9.734179	0.020518	0.047031	-0.017054
+4.063415	-0.196312	-0.414169	9.750937	0.018919	0.045698	-0.017054
+4.064399	-0.198706	-0.380653	9.717420	0.018919	0.044899	-0.015455
+4.065400	-0.167583	-0.435716	9.789242	0.019052	0.045432	-0.014256
+4.066399	-0.181947	-0.380653	9.762907	0.018919	0.045565	-0.014522
+4.067399	-0.138854	-0.399805	9.784454	0.019185	0.046498	-0.016920
+4.068399	-0.181947	-0.433322	9.703056	0.018253	0.047963	-0.017720
+4.069476	-0.193917	-0.397411	9.734179	0.018253	0.047963	-0.017720
+4.070441	-0.169977	-0.397411	9.762907	0.019851	0.046498	-0.017720
+4.071479	-0.136460	-0.402199	9.784454	0.019185	0.046764	-0.017453
+4.072480	-0.179553	-0.442898	9.789242	0.018786	0.046764	-0.017320
+4.073482	-0.172371	-0.402199	9.748543	0.019452	0.047164	-0.017320
+4.074480	-0.177159	-0.387835	9.786848	0.020651	0.046364	-0.018786
+4.075479	-0.150825	-0.442898	9.849093	0.019319	0.045032	-0.019718
+4.076479	-0.174765	-0.447686	9.813182	0.019052	0.046364	-0.018652
+4.077483	-0.131672	-0.406987	9.837123	0.018786	0.047031	-0.017320
+4.078479	-0.184341	-0.380653	9.808394	0.018786	0.045832	-0.016254
+4.079386	-0.172371	-0.375865	9.722208	0.019851	0.046498	-0.015055
+4.080405	-0.138854	-0.454868	9.753331	0.019319	0.046631	-0.015055
+4.081399	-0.189129	-0.447686	9.753331	0.019185	0.048230	-0.016654
+4.082397	-0.155613	-0.445292	9.726997	0.019585	0.048629	-0.015855
+4.083398	-0.160401	-0.385441	9.798818	0.019052	0.047297	-0.014922
+4.084394	-0.153219	-0.397411	9.858669	0.018919	0.046764	-0.015322
+4.085479	-0.129278	-0.390229	9.827546	0.019452	0.047830	-0.016521
+4.086395	-0.169977	-0.368683	9.832334	0.019718	0.047564	-0.015988
+4.087482	-0.148431	-0.423746	9.849093	0.018386	0.046764	-0.014922
+4.088480	-0.162795	-0.416563	9.798818	0.017853	0.047430	-0.014655
+4.089452	-0.136460	-0.361500	9.829940	0.018652	0.047963	-0.015055
+4.090436	-0.155613	-0.375865	9.813182	0.019185	0.046897	-0.015455
+4.091482	-0.119702	-0.385441	9.777271	0.019052	0.046498	-0.016387
+4.092480	-0.155613	-0.414169	9.834729	0.018119	0.047430	-0.016787
+4.093482	-0.138854	-0.409381	9.765301	0.017587	0.047830	-0.016920
+4.094479	-0.150825	-0.373471	9.794030	0.018919	0.046764	-0.016254
+4.095480	-0.105338	-0.395017	9.815576	0.019718	0.046231	-0.016654
+4.096404	-0.131672	-0.428534	9.734179	0.019185	0.046897	-0.016920
+4.097399	-0.160401	-0.440504	9.736573	0.020384	0.047430	-0.018786
+4.098386	-0.148431	-0.404593	9.779666	0.020251	0.048230	-0.018386
+4.099399	-0.169977	-0.402199	9.865851	0.018253	0.047031	-0.016654
+4.100380	-0.143643	-0.354318	9.750937	0.018519	0.045965	-0.017720
+4.101403	-0.201100	-0.409381	9.724603	0.018786	0.046364	-0.017587
+4.102401	-0.131672	-0.406987	9.834729	0.019185	0.046498	-0.019052
+4.103400	-0.158007	-0.416563	9.865851	0.018786	0.045432	-0.020917
+4.104397	-0.126884	-0.459656	9.870639	0.019052	0.045832	-0.019319
+4.105399	-0.155613	-0.418958	9.825152	0.018386	0.045432	-0.018253
+4.106399	-0.126884	-0.378259	9.726997	0.018519	0.043833	-0.019985
+4.107399	-0.150825	-0.392623	9.698268	0.017453	0.043966	-0.021450
+4.108398	-0.179553	-0.399805	9.762907	0.016254	0.044100	-0.021450
+4.109399	-0.167583	-0.397411	9.762907	0.016121	0.043833	-0.022916
+4.110399	-0.191523	-0.423746	9.782060	0.016121	0.043034	-0.023049
+4.111390	-0.162795	-0.485991	9.832334	0.015055	0.041968	-0.021583
+4.112399	-0.138854	-0.433322	9.774877	0.015188	0.042101	-0.021184
+4.113399	-0.114914	-0.416563	9.748543	0.014522	0.043167	-0.022649
+4.114387	-0.148431	-0.387835	9.750937	0.014789	0.044766	-0.022783
+4.115400	-0.136460	-0.366289	9.774877	0.016254	0.046764	-0.021583
+4.116400	-0.136460	-0.411775	9.825152	0.017587	0.046231	-0.021184
+4.117401	-0.131672	-0.406987	9.746149	0.018119	0.045032	-0.019718
+4.118398	-0.119702	-0.452474	9.755725	0.018119	0.045698	-0.021184
+4.119398	-0.122096	-0.409381	9.770089	0.018253	0.045965	-0.023982
+4.120399	-0.126884	-0.423746	9.782060	0.018786	0.045965	-0.023848
+4.121398	-0.136460	-0.421352	9.767695	0.019052	0.046498	-0.022916
+4.122397	-0.131672	-0.390229	9.841911	0.019185	0.048096	-0.023715
+4.123399	-0.160401	-0.409381	9.827546	0.021583	0.047963	-0.022916
+4.124398	-0.167583	-0.440504	9.820364	0.021317	0.047297	-0.022383
+4.125400	-0.153219	-0.433322	9.731785	0.020384	0.047430	-0.022516
+4.126399	-0.158007	-0.347136	9.782060	0.019718	0.047297	-0.021450
+4.127391	-0.107732	-0.402199	9.841911	0.019319	0.047297	-0.021717
+4.128398	-0.064639	-0.395017	9.753331	0.019585	0.048896	-0.022516
+4.129399	-0.090974	-0.406987	9.782060	0.020384	0.049429	-0.023982
+4.130398	-0.162795	-0.359106	9.815576	0.020917	0.049029	-0.024115
+4.131398	-0.126884	-0.351924	9.760513	0.018786	0.049162	-0.023049
+4.132400	-0.138854	-0.435716	9.794030	0.019319	0.048363	-0.022250
+4.133399	-0.088580	-0.476415	9.717420	0.020384	0.047164	-0.022783
+4.134479	-0.110126	-0.387835	9.712632	0.020118	0.048363	-0.023715
+4.135422	-0.131672	-0.375865	9.741361	0.019718	0.049029	-0.024381
+4.136411	-0.102944	-0.411775	9.794030	0.018519	0.047830	-0.023848
+4.137482	-0.095762	-0.466838	9.832334	0.017587	0.045965	-0.023315
+4.138475	-0.167583	-0.373471	9.832334	0.018119	0.046631	-0.021717
+4.139477	-0.162795	-0.373471	9.779666	0.019585	0.048363	-0.021717
+4.140480	-0.150825	-0.402199	9.772483	0.019585	0.047830	-0.020784
+4.141433	-0.167583	-0.397411	9.686298	0.017853	0.045565	-0.020518
+4.142480	-0.177159	-0.387835	9.676722	0.017054	0.045165	-0.021583
+4.143439	-0.126884	-0.418958	9.755725	0.017720	0.045432	-0.023582
+4.144428	-0.095762	-0.416563	9.791636	0.017986	0.045698	-0.024115
+4.145410	-0.119702	-0.397411	9.779666	0.017320	0.046231	-0.024381
+4.146409	-0.093368	-0.397411	9.820364	0.015988	0.045698	-0.023982
+4.147398	-0.112520	-0.380653	9.829940	0.014922	0.041968	-0.023582
+4.148404	-0.162795	-0.387835	9.777271	0.014256	0.040369	-0.021983
+4.149394	-0.191523	-0.399805	9.712632	0.012790	0.040236	-0.021983
+4.150384	-0.165189	-0.385441	9.731785	0.013323	0.042634	-0.023315
+4.151403	-0.081397	-0.368683	9.803606	0.013856	0.045832	-0.023449
+4.152479	-0.172371	-0.366289	9.858669	0.015322	0.046364	-0.022516
+4.153482	-0.153219	-0.435716	9.815576	0.017986	0.046764	-0.022250
+4.154479	-0.114914	-0.469232	9.841911	0.018519	0.048763	-0.021850
+4.155475	-0.162795	-0.416563	9.861063	0.018119	0.049162	-0.022250
+4.156479	-0.169977	-0.397411	9.841911	0.018919	0.046897	-0.023182
+4.157481	-0.193917	-0.399805	9.870639	0.018919	0.046631	-0.022516
+4.158483	-0.169977	-0.375865	9.820364	0.019185	0.048896	-0.022383
+4.159427	-0.165189	-0.366289	9.746149	0.020118	0.050628	-0.021450
+4.160478	-0.169977	-0.395017	9.789242	0.021051	0.051427	-0.023182
+4.161421	-0.134066	-0.402199	9.748543	0.020917	0.051560	-0.022916
+4.162481	-0.131672	-0.416563	9.746149	0.019585	0.049962	-0.023182
+4.163421	-0.110126	-0.404593	9.719814	0.019985	0.048363	-0.021850
+4.164399	-0.191523	-0.392623	9.734179	0.021717	0.048629	-0.022783
+4.165399	-0.172371	-0.440504	9.743755	0.022383	0.049962	-0.021850
+4.166397	-0.150825	-0.416563	9.779666	0.022250	0.051560	-0.021983
+4.167397	-0.105338	-0.430928	9.767695	0.021583	0.051028	-0.023049
+4.168427	-0.143643	-0.459656	9.770089	0.021051	0.050228	-0.022250
+4.169482	-0.129278	-0.406987	9.772483	0.020251	0.051161	-0.020917
+4.170444	-0.169977	-0.387835	9.813182	0.020518	0.051694	-0.020651
+4.171476	-0.090974	-0.392623	9.839517	0.020784	0.052360	-0.022649
+4.172484	-0.146037	-0.395017	9.803606	0.020651	0.051427	-0.023049
+4.173477	-0.174765	-0.395017	9.717420	0.021983	0.051028	-0.020518
+4.174481	-0.160401	-0.373471	9.695874	0.022250	0.050761	-0.019718
+4.175479	-0.138854	-0.423746	9.710238	0.021184	0.050761	-0.022383
+4.176482	-0.114914	-0.409381	9.796424	0.021184	0.049962	-0.022250
+4.177482	-0.155613	-0.366289	9.846699	0.022383	0.049296	-0.021983
+4.178481	-0.134066	-0.447686	9.774877	0.022116	0.049828	-0.021317
+4.179417	-0.172371	-0.450080	9.810788	0.021850	0.050228	-0.021983
+4.180399	-0.203494	-0.411775	9.734179	0.021184	0.050095	-0.021450
+4.181401	-0.225040	-0.383047	9.767695	0.020518	0.049029	-0.022516
+4.182400	-0.193917	-0.387835	9.734179	0.019851	0.050228	-0.023449
+4.183400	-0.177159	-0.402199	9.717420	0.021051	0.051560	-0.022516
+4.184399	-0.150825	-0.433322	9.782060	0.021583	0.051694	-0.022516
+4.185480	-0.114914	-0.445292	9.774877	0.020251	0.050495	-0.022916
+4.186438	-0.193917	-0.416563	9.794030	0.020251	0.050228	-0.023848
+4.187481	-0.162795	-0.380653	9.724603	0.020251	0.050361	-0.022649
+4.188479	-0.129278	-0.416563	9.614477	0.020384	0.050894	-0.021317
+4.189441	-0.143643	-0.459656	9.758119	0.021583	0.051427	-0.021317
+4.190436	-0.186735	-0.406987	9.789242	0.021450	0.050894	-0.021717
+4.191408	-0.143643	-0.406987	9.791636	0.021317	0.051161	-0.022783
+4.192418	-0.162795	-0.428534	9.734179	0.021983	0.051827	-0.021983
+4.193497	-0.165189	-0.395017	9.767695	0.021983	0.050761	-0.021850
+4.194499	-0.107732	-0.406987	9.741361	0.020784	0.049695	-0.022649
+4.195437	-0.191523	-0.411775	9.703056	0.019851	0.049562	-0.022783
+4.196496	-0.129278	-0.385441	9.779666	0.020784	0.050628	-0.022916
+4.197397	-0.100550	-0.409381	9.806000	0.020917	0.051161	-0.023582
+4.198416	-0.124490	-0.438110	9.715026	0.021717	0.049162	-0.024115
+4.199416	-0.217858	-0.406987	9.779666	0.021051	0.051294	-0.023715
+4.200415	-0.148431	-0.399805	9.853881	0.020118	0.051694	-0.025047
+4.201416	-0.162795	-0.409381	9.784454	0.019585	0.050095	-0.024515
+4.202415	-0.129278	-0.411775	9.782060	0.020784	0.050894	-0.022383
+4.203396	-0.174765	-0.428534	9.760513	0.021583	0.051294	-0.021717
+4.204469	-0.143643	-0.418958	9.777271	0.020384	0.049828	-0.021583
+4.205405	-0.107732	-0.402199	9.832334	0.021051	0.051028	-0.022116
+4.206395	-0.150825	-0.399805	9.877821	0.021317	0.051028	-0.022916
+4.207406	-0.143643	-0.380653	9.789242	0.020784	0.050095	-0.022649
+4.208426	-0.122096	-0.378259	9.738967	0.021184	0.050761	-0.022783
+4.209500	-0.105338	-0.399805	9.712632	0.021317	0.052493	-0.023049
+4.210500	-0.088580	-0.383047	9.707844	0.020784	0.051960	-0.022783
+4.211443	-0.136460	-0.375865	9.755725	0.019585	0.051294	-0.022116
+4.212485	-0.160401	-0.342348	9.794030	0.020118	0.050628	-0.022383
+4.213415	-0.126884	-0.361500	9.782060	0.021051	0.050495	-0.023315
+4.214414	-0.102944	-0.411775	9.827546	0.021850	0.051827	-0.024248
+4.215415	-0.153219	-0.359106	9.849093	0.022783	0.052760	-0.023449
+4.216412	-0.165189	-0.416563	9.825152	0.022116	0.051960	-0.022250
+4.217396	-0.153219	-0.471626	9.750937	0.021450	0.052093	-0.022250
+4.218395	-0.134066	-0.406987	9.750937	0.021317	0.051694	-0.024115
+4.219413	-0.160401	-0.442898	9.803606	0.020384	0.050894	-0.023582
+4.220477	-0.122096	-0.435716	9.786848	0.020518	0.051161	-0.022116
+4.221476	-0.119702	-0.378259	9.758119	0.020917	0.050361	-0.023182
+4.222477	-0.165189	-0.373471	9.712632	0.020384	0.050361	-0.023049
+4.223419	-0.131672	-0.387835	9.801212	0.019452	0.050761	-0.022516
+4.224468	-0.110126	-0.457262	9.810788	0.020384	0.051427	-0.022383
+4.225479	-0.110126	-0.406987	9.753331	0.021051	0.051827	-0.022783
+4.226474	-0.134066	-0.363895	9.774877	0.021317	0.051427	-0.022516
+4.227475	-0.162795	-0.392623	9.712632	0.020784	0.049962	-0.023848
+4.228470	-0.181947	-0.378259	9.806000	0.019319	0.050628	-0.025714
+4.229401	-0.138854	-0.416563	9.803606	0.019052	0.051827	-0.023449
+4.230395	-0.186735	-0.418958	9.803606	0.019052	0.051294	-0.021583
+4.231395	-0.172371	-0.418958	9.834729	0.019052	0.050095	-0.021583
+4.232394	-0.186735	-0.478809	9.817970	0.020118	0.050894	-0.021983
+4.233418	-0.167583	-0.416563	9.808394	0.020384	0.050628	-0.023582
+4.234420	-0.205888	-0.387835	9.789242	0.019985	0.049162	-0.023049
+4.235495	-0.181947	-0.452474	9.746149	0.020251	0.049562	-0.021850
+4.236499	-0.119702	-0.404593	9.748543	0.019718	0.050894	-0.022383
+4.237409	-0.167583	-0.378259	9.851487	0.020917	0.050095	-0.022250
+4.238498	-0.155613	-0.404593	9.858669	0.020384	0.049162	-0.024248
+4.239500	-0.203494	-0.426140	9.863457	0.020118	0.049296	-0.023982
+4.240500	-0.138854	-0.416563	9.942460	0.020384	0.049162	-0.022116
+4.241499	-0.124490	-0.406987	9.791636	0.021184	0.048763	-0.021051
+4.242504	-0.114914	-0.380653	9.760513	0.021317	0.049162	-0.022116
+4.243454	-0.126884	-0.430928	9.738967	0.020784	0.050495	-0.023449
+4.244497	-0.150825	-0.462050	9.731785	0.020118	0.050894	-0.023182
+4.245503	-0.129278	-0.457262	9.758119	0.020651	0.049562	-0.022383
+4.246425	-0.122096	-0.409381	9.832334	0.020251	0.049296	-0.022250
+4.247411	-0.155613	-0.423746	9.810788	0.021317	0.049562	-0.024248
+4.248416	-0.172371	-0.406987	9.794030	0.022116	0.050495	-0.022916
+4.249417	-0.153219	-0.409381	9.794030	0.021983	0.050361	-0.021983
+4.250416	-0.076609	-0.406987	9.849093	0.021317	0.050095	-0.021983
+4.251416	-0.134066	-0.371077	9.856275	0.021850	0.050628	-0.022649
+4.252399	-0.143643	-0.363895	9.774877	0.021717	0.050894	-0.023315
+4.253465	-0.220252	-0.390229	9.758119	0.022250	0.050761	-0.024115
+4.254479	-0.205888	-0.416563	9.743755	0.022649	0.050761	-0.024781
+4.255499	-0.131672	-0.397411	9.815576	0.022649	0.050894	-0.024248
+4.256499	-0.136460	-0.450080	9.789242	0.021717	0.051294	-0.023848
+4.257504	-0.162795	-0.380653	9.767695	0.021184	0.051827	-0.022783
+4.258500	-0.198706	-0.373471	9.729391	0.021850	0.052227	-0.022916
+4.259501	-0.148431	-0.361500	9.736573	0.021184	0.051827	-0.023182
+4.260499	-0.138854	-0.361500	9.717420	0.020917	0.050628	-0.021717
+4.261458	-0.169977	-0.411775	9.731785	0.021717	0.050495	-0.020651
+4.262422	-0.136460	-0.406987	9.801212	0.022516	0.051960	-0.020518
+4.263430	-0.122096	-0.421352	9.724603	0.022783	0.051694	-0.020917
+4.264411	-0.134066	-0.414169	9.722208	0.022116	0.051028	-0.021051
+4.265418	-0.150825	-0.378259	9.736573	0.021850	0.051161	-0.021583
+4.266416	-0.191523	-0.428534	9.726997	0.021184	0.052360	-0.023049
+4.267416	-0.165189	-0.392623	9.817970	0.021983	0.052626	-0.022649
+4.268411	-0.162795	-0.385441	9.808394	0.022383	0.052760	-0.022916
+4.269500	-0.177159	-0.493173	9.817970	0.021717	0.052493	-0.024515
+4.270499	-0.174765	-0.426140	9.762907	0.021450	0.050894	-0.024381
+4.271512	-0.239404	-0.409381	9.741361	0.022649	0.051960	-0.023449
+4.272444	-0.184341	-0.366289	9.801212	0.022516	0.053292	-0.023049
+4.273501	-0.112520	-0.395017	9.774877	0.021850	0.052493	-0.021450
+4.274499	-0.165189	-0.390229	9.803606	0.022250	0.052360	-0.021850
+4.275500	-0.155613	-0.342348	9.729391	0.022783	0.052493	-0.023315
+4.276503	-0.177159	-0.426140	9.767695	0.021850	0.051827	-0.023182
+4.277497	-0.138854	-0.452474	9.798818	0.020518	0.051960	-0.022116
+4.278499	-0.153219	-0.430928	9.779666	0.021051	0.053026	-0.023315
+4.279496	-0.186735	-0.378259	9.806000	0.021051	0.054225	-0.023848
+4.280424	-0.177159	-0.414169	9.767695	0.021583	0.054225	-0.023982
+4.281415	-0.134066	-0.409381	9.741361	0.022116	0.054092	-0.023848
+4.282423	-0.102944	-0.488385	9.758119	0.022383	0.053159	-0.023715
+4.283398	-0.105338	-0.392623	9.743755	0.022516	0.052893	-0.022516
+4.284415	-0.119702	-0.383047	9.803606	0.022516	0.053959	-0.023715
+4.285419	-0.131672	-0.397411	9.786848	0.021583	0.054358	-0.022916
+4.286423	-0.143643	-0.361500	9.683904	0.020651	0.055424	-0.022916
+4.287396	-0.117308	-0.399805	9.767695	0.021850	0.054625	-0.021983
+4.288419	-0.136460	-0.397411	9.784454	0.023049	0.053559	-0.021583
+4.289421	-0.105338	-0.411775	9.794030	0.022649	0.054758	-0.023582
+4.290419	-0.117308	-0.421352	9.784454	0.023182	0.055158	-0.024648
+4.291416	-0.067033	-0.430928	9.794030	0.022649	0.054358	-0.025980
+4.292408	-0.059851	-0.430928	9.774877	0.022516	0.054625	-0.025181
+4.293421	-0.148431	-0.447686	9.748543	0.022516	0.054891	-0.024248
+4.294419	-0.138854	-0.411775	9.734179	0.023182	0.054758	-0.023049
+4.295418	-0.105338	-0.397411	9.698268	0.023715	0.055158	-0.024781
+4.296398	-0.095762	-0.375865	9.832334	0.023182	0.055824	-0.025980
+4.297398	-0.057457	-0.383047	9.789242	0.023049	0.055824	-0.026380
+4.298392	-0.026334	-0.378259	9.772483	0.024115	0.055691	-0.027579
+4.299398	-0.038305	-0.409381	9.825152	0.024115	0.056890	-0.029577
+4.300397	-0.059851	-0.416563	9.789242	0.023315	0.056890	-0.032109
+4.301384	-0.083792	-0.371077	9.786848	0.022783	0.056623	-0.034640
+4.302379	-0.138854	-0.390229	9.813182	0.023582	0.056224	-0.033441
+4.303372	-0.193917	-0.426140	9.772483	0.024115	0.055824	-0.032109
+4.304380	-0.193917	-0.414169	9.652781	0.024914	0.056357	-0.033841
+4.305384	-0.227434	-0.409381	9.717420	0.024648	0.055557	-0.034507
+4.306381	-0.227434	-0.363895	9.806000	0.023182	0.055557	-0.033441
+4.307387	-0.179553	-0.375865	9.700662	0.022116	0.055424	-0.032775
+4.308378	-0.129278	-0.390229	9.659963	0.020518	0.053159	-0.031309
+4.309386	-0.198706	-0.378259	9.700662	0.020251	0.051694	-0.030110
+4.310384	-0.179553	-0.378259	9.681510	0.021583	0.051294	-0.032375
+4.311384	-0.153219	-0.380653	9.679116	0.021450	0.050628	-0.033574
+4.312383	-0.191523	-0.438110	9.784454	0.021051	0.049828	-0.029577
+4.313365	-0.129278	-0.406987	9.710238	0.020651	0.050095	-0.028112
+4.314356	-0.110126	-0.375865	9.762907	0.020784	0.051028	-0.028778
+4.315374	-0.165189	-0.404593	9.750937	0.019985	0.051161	-0.030776
+4.316377	-0.136460	-0.409381	9.662357	0.019185	0.051560	-0.031709
+4.317386	-0.117308	-0.402199	9.755725	0.019718	0.051028	-0.029044
+4.318383	-0.110126	-0.375865	9.755725	0.021583	0.050761	-0.027446
+4.319378	-0.160401	-0.385441	9.803606	0.019319	0.051427	-0.028112
+4.320446	-0.160401	-0.423746	9.841911	0.017986	0.051161	-0.028645
+4.321448	-0.167583	-0.411775	9.851487	0.019319	0.051161	-0.028645
+4.322449	-0.177159	-0.418958	9.817970	0.021051	0.052227	-0.028778
+4.323448	-0.155613	-0.414169	9.758119	0.020651	0.052093	-0.029044
+4.324442	-0.112520	-0.368683	9.767695	0.020518	0.051694	-0.027712
+4.325445	-0.138854	-0.395017	9.808394	0.020917	0.050761	-0.026513
+4.326434	-0.148431	-0.351924	9.834729	0.020118	0.050628	-0.027179
+4.327464	-0.155613	-0.387835	9.873033	0.020384	0.050761	-0.027579
+4.328448	-0.172371	-0.409381	9.784454	0.020784	0.051427	-0.025447
+4.329388	-0.169977	-0.416563	9.712632	0.021717	0.050628	-0.024781
+4.330371	-0.203494	-0.454868	9.791636	0.020384	0.050095	-0.025980
+4.331368	-0.172371	-0.430928	9.767695	0.019585	0.050628	-0.025980
+4.332382	-0.141249	-0.433322	9.815576	0.021184	0.051960	-0.025447
+4.333398	-0.172371	-0.392623	9.789242	0.021317	0.052227	-0.025181
+4.334397	-0.169977	-0.392623	9.806000	0.020251	0.052227	-0.024781
+4.335402	-0.155613	-0.409381	9.808394	0.020118	0.051560	-0.025181
+4.336400	-0.129278	-0.454868	9.877821	0.021317	0.051427	-0.023982
+4.337380	-0.179553	-0.409381	9.794030	0.021450	0.052093	-0.023982
+4.338429	-0.179553	-0.366289	9.753331	0.020251	0.053559	-0.022783
+4.339454	-0.169977	-0.430928	9.755725	0.020917	0.052893	-0.023982
+4.340448	-0.169977	-0.414169	9.750937	0.021317	0.051560	-0.025314
+4.341449	-0.134066	-0.363895	9.729391	0.020917	0.051427	-0.026779
+4.342445	-0.143643	-0.373471	9.712632	0.020651	0.052493	-0.027179
+4.343449	-0.153219	-0.409381	9.820364	0.021850	0.052626	-0.025980
+4.344448	-0.150825	-0.459656	9.808394	0.021983	0.050628	-0.026380
+4.345447	-0.227434	-0.452474	9.810788	0.021184	0.051427	-0.025181
+4.346363	-0.181947	-0.380653	9.817970	0.020118	0.052760	-0.025047
+4.347357	-0.155613	-0.416563	9.760513	0.021450	0.053559	-0.025447
+4.348343	-0.160401	-0.421352	9.765301	0.022116	0.053159	-0.026113
+4.349346	-0.155613	-0.450080	9.813182	0.021850	0.050894	-0.026113
+4.350353	-0.126884	-0.371077	9.877821	0.021051	0.051161	-0.026247
+4.351353	-0.146037	-0.383047	9.834729	0.021450	0.052626	-0.025181
+4.352448	-0.122096	-0.409381	9.791636	0.021450	0.051427	-0.025847
+4.353354	-0.098156	-0.423746	9.806000	0.020384	0.051827	-0.025047
+4.354347	-0.174765	-0.411775	9.753331	0.019985	0.050495	-0.025714
+4.355335	-0.234616	-0.414169	9.844305	0.019585	0.051028	-0.027979
+4.356343	-0.213070	-0.402199	9.810788	0.019851	0.051028	-0.027312
+4.357349	-0.124490	-0.385441	9.772483	0.020384	0.049162	-0.024381
+4.358344	-0.205888	-0.445292	9.762907	0.020118	0.049562	-0.024248
+4.359369	-0.177159	-0.450080	9.772483	0.020251	0.049296	-0.025714
+4.360448	-0.181947	-0.426140	9.789242	0.021051	0.048896	-0.025980
+4.361432	-0.193917	-0.418958	9.700662	0.021317	0.048230	-0.024914
+4.362380	-0.186735	-0.359106	9.741361	0.020518	0.047963	-0.026113
+4.363367	-0.210676	-0.404593	9.791636	0.021051	0.047697	-0.025847
+4.364369	-0.213070	-0.390229	9.794030	0.020917	0.047963	-0.025047
+4.365418	-0.203494	-0.361500	9.786848	0.020384	0.048763	-0.023715
+4.366497	-0.193917	-0.402199	9.789242	0.020384	0.047963	-0.024381
+4.367498	-0.179553	-0.445292	9.789242	0.020917	0.048496	-0.024648
+4.368501	-0.165189	-0.414169	9.765301	0.019985	0.049162	-0.024248
+4.369499	-0.172371	-0.406987	9.892186	0.020118	0.048763	-0.023582
+4.370499	-0.141249	-0.397411	9.794030	0.019985	0.049029	-0.022250
+4.371440	-0.174765	-0.390229	9.782060	0.019851	0.048363	-0.021717
+4.372494	-0.112520	-0.404593	9.774877	0.019052	0.047963	-0.022783
+4.373501	-0.172371	-0.383047	9.719814	0.021184	0.048230	-0.023449
+4.374499	-0.186735	-0.385441	9.674328	0.021717	0.047164	-0.023449
+4.375497	-0.196312	-0.373471	9.767695	0.020251	0.046897	-0.023182
+4.376499	-0.155613	-0.366289	9.808394	0.019319	0.048363	-0.022916
+4.377499	-0.177159	-0.375865	9.794030	0.019718	0.048096	-0.022383
+4.378499	-0.129278	-0.368683	9.839517	0.019851	0.047031	-0.022649
+4.379441	-0.138854	-0.337560	9.798818	0.019052	0.045165	-0.022383
+4.380422	-0.172371	-0.399805	9.856275	0.018253	0.046498	-0.023315
+4.381412	-0.105338	-0.414169	9.743755	0.019585	0.048230	-0.024648
+4.382416	-0.112520	-0.397411	9.794030	0.020784	0.046897	-0.023582
+4.383416	-0.165189	-0.402199	9.851487	0.020784	0.045698	-0.021450
+4.384415	-0.169977	-0.435716	9.770089	0.019319	0.047297	-0.022250
+4.385372	-0.126884	-0.426140	9.779666	0.017853	0.049162	-0.023049
+4.386448	-0.122096	-0.363895	9.851487	0.018519	0.049562	-0.023449
+4.387388	-0.155613	-0.402199	9.820364	0.020118	0.048096	-0.021850
+4.388379	-0.090974	-0.421352	9.815576	0.022250	0.047697	-0.023449
+4.389398	-0.069427	-0.392623	9.786848	0.020518	0.049162	-0.023982
+4.390398	-0.088580	-0.411775	9.765301	0.019319	0.049429	-0.023582
+4.391375	-0.102944	-0.337560	9.767695	0.020651	0.047297	-0.020651
+4.392442	-0.134066	-0.363895	9.760513	0.020118	0.046897	-0.021184
+4.393449	-0.162795	-0.442898	9.736573	0.020784	0.049029	-0.024381
+4.394446	-0.172371	-0.445292	9.782060	0.021317	0.050361	-0.023982
+4.395446	-0.162795	-0.421352	9.777271	0.020651	0.048629	-0.023848
+4.396388	-0.153219	-0.354318	9.786848	0.021051	0.048496	-0.023715
+4.397416	-0.160401	-0.423746	9.786848	0.020917	0.049162	-0.023582
+4.398414	-0.148431	-0.409381	9.738967	0.020917	0.050228	-0.021717
+4.399415	-0.155613	-0.356712	9.758119	0.021850	0.050228	-0.020917
+4.400414	-0.160401	-0.402199	9.753331	0.021983	0.049828	-0.022116
+4.401458	-0.143643	-0.445292	9.691086	0.021184	0.051028	-0.022916
+4.402415	-0.141249	-0.428534	9.741361	0.021583	0.050761	-0.022383
+4.403459	-0.167583	-0.359106	9.820364	0.021317	0.050361	-0.021184
+4.404503	-0.198706	-0.418958	9.806000	0.021317	0.050628	-0.022116
+4.405501	-0.167583	-0.466838	9.791636	0.021983	0.051161	-0.021717
+4.406496	-0.119702	-0.459656	9.786848	0.021184	0.051161	-0.021051
+4.407499	-0.150825	-0.438110	9.841911	0.021051	0.051028	-0.019851
+4.408498	-0.181947	-0.462050	9.868245	0.021051	0.050095	-0.021051
+4.409499	-0.134066	-0.395017	9.868245	0.021051	0.050761	-0.021583
+4.410471	-0.079003	-0.409381	9.817970	0.019985	0.050761	-0.021184
+4.411491	-0.150825	-0.418958	9.736573	0.019185	0.051694	-0.020651
+4.412496	-0.131672	-0.442898	9.815576	0.019585	0.052360	-0.021583
+4.413426	-0.122096	-0.402199	9.782060	0.020118	0.051294	-0.023049
+4.414418	-0.146037	-0.399805	9.738967	0.020118	0.050361	-0.021850
+4.415411	-0.177159	-0.387835	9.803606	0.021051	0.050628	-0.021850
+4.416411	-0.138854	-0.395017	9.736573	0.021184	0.051294	-0.021450
+4.417405	-0.141249	-0.387835	9.729391	0.019985	0.052893	-0.021317
+4.418399	-0.141249	-0.387835	9.729391	0.019985	0.053026	-0.021051
+4.419484	-0.155613	-0.368683	9.734179	0.021583	0.052493	-0.021450
+4.420454	-0.114914	-0.380653	9.779666	0.022516	0.052626	-0.021583
+4.421444	-0.141249	-0.387835	9.772483	0.023315	0.053026	-0.022250
+4.422484	-0.153219	-0.392623	9.827546	0.022516	0.054092	-0.020917
+4.423484	-0.143643	-0.390229	9.753331	0.021850	0.054092	-0.019585
+4.424484	-0.136460	-0.402199	9.755725	0.022116	0.053292	-0.021317
+4.425484	-0.143643	-0.445292	9.777271	0.021184	0.052227	-0.021717
+4.426481	-0.143643	-0.466838	9.801212	0.021317	0.052227	-0.020917
+4.427482	-0.158007	-0.397411	9.784454	0.020917	0.052227	-0.021450
+4.428482	-0.124490	-0.423746	9.748543	0.020518	0.053026	-0.022649
+4.429405	-0.146037	-0.354318	9.698268	0.020784	0.054758	-0.022250
+4.430404	-0.112520	-0.327984	9.681510	0.021450	0.054758	-0.020917
+4.431397	-0.098156	-0.339954	9.765301	0.021983	0.053159	-0.021717
+4.432399	-0.150825	-0.402199	9.770089	0.021051	0.052360	-0.020917
+4.433418	-0.201100	-0.438110	9.820364	0.020917	0.052760	-0.021850
+4.434416	-0.148431	-0.411775	9.777271	0.021983	0.053426	-0.021983
+4.435496	-0.110126	-0.385441	9.779666	0.021583	0.052893	-0.021450
+4.436499	-0.160401	-0.375865	9.815576	0.021583	0.053692	-0.020518
+4.437441	-0.167583	-0.351924	9.851487	0.020384	0.054225	-0.019585
+4.438499	-0.138854	-0.411775	9.743755	0.020251	0.053692	-0.020518
+4.439455	-0.110126	-0.438110	9.782060	0.019452	0.054092	-0.020917
+4.440457	-0.155613	-0.442898	9.767695	0.019585	0.052760	-0.021051
+4.441498	-0.162795	-0.375865	9.700662	0.020518	0.052760	-0.021184
+4.442423	-0.160401	-0.385441	9.801212	0.020518	0.053292	-0.021450
+4.443496	-0.119702	-0.361500	9.829940	0.021184	0.053026	-0.019985
+4.444499	-0.117308	-0.399805	9.798818	0.020917	0.053292	-0.021450
+4.445463	-0.172371	-0.428534	9.765301	0.021983	0.053159	-0.023049
+4.446410	-0.181947	-0.414169	9.712632	0.022116	0.053026	-0.022649
+4.447415	-0.119702	-0.414169	9.779666	0.022116	0.055025	-0.023049
+4.448382	-0.124490	-0.371077	9.798818	0.021051	0.054758	-0.022649
+4.449416	-0.110126	-0.402199	9.765301	0.020118	0.054625	-0.021184
+4.450390	-0.143643	-0.387835	9.719814	0.019718	0.053959	-0.021850
+4.451412	-0.102944	-0.423746	9.770089	0.019985	0.051960	-0.021450
+4.452416	-0.129278	-0.421352	9.851487	0.020251	0.052493	-0.021450
+4.453481	-0.146037	-0.404593	9.784454	0.021051	0.053159	-0.022250
+4.454499	-0.153219	-0.402199	9.832334	0.020251	0.052626	-0.021850
+4.455496	-0.129278	-0.414169	9.755725	0.020518	0.053159	-0.019985
+4.456499	-0.117308	-0.383047	9.746149	0.020784	0.053026	-0.019718
+4.457499	-0.148431	-0.371077	9.731785	0.020917	0.052493	-0.021450
+4.458409	-0.090974	-0.383047	9.671934	0.021450	0.053959	-0.022783
+4.459442	-0.086186	-0.385441	9.717420	0.022516	0.054758	-0.022250
+4.460497	-0.136460	-0.418958	9.837123	0.022916	0.053959	-0.021717
+4.461502	-0.153219	-0.418958	9.868245	0.022116	0.052360	-0.020518
+4.462475	-0.160401	-0.390229	9.810788	0.020518	0.051827	-0.020784
+4.463415	-0.153219	-0.373471	9.712632	0.019185	0.053292	-0.022116
+4.464416	-0.098156	-0.366289	9.703056	0.019319	0.054492	-0.023582
+4.465409	-0.146037	-0.418958	9.782060	0.019985	0.052626	-0.022383
+4.466415	-0.177159	-0.416563	9.712632	0.020917	0.051827	-0.020651
+4.467415	-0.172371	-0.409381	9.741361	0.021317	0.052093	-0.020917
+4.468416	-0.167583	-0.366289	9.750937	0.020651	0.051960	-0.021850
+4.469352	-0.146037	-0.387835	9.803606	0.019985	0.051427	-0.021717
+4.470341	-0.162795	-0.411775	9.803606	0.019851	0.052493	-0.022649
+4.471423	-0.124490	-0.366289	9.806000	0.020784	0.051960	-0.021317
+4.472443	-0.148431	-0.402199	9.820364	0.021317	0.050894	-0.021450
+4.473448	-0.160401	-0.363895	9.801212	0.020651	0.052227	-0.022250
+4.474446	-0.146037	-0.308832	9.738967	0.022250	0.052093	-0.023582
+4.475448	-0.117308	-0.351924	9.743755	0.021317	0.051960	-0.022116
+4.476443	-0.114914	-0.354318	9.801212	0.020518	0.053159	-0.020518
+4.477448	-0.189129	-0.332772	9.765301	0.020518	0.051028	-0.022649
+4.478447	-0.162795	-0.318408	9.750937	0.020518	0.050761	-0.023049
+4.479434	-0.105338	-0.368683	9.712632	0.020651	0.052626	-0.022116
+4.480377	-0.090974	-0.464444	9.729391	0.019585	0.052493	-0.022649
+4.481417	-0.105338	-0.445292	9.813182	0.020917	0.051560	-0.023449
+4.482416	-0.143643	-0.423746	9.858669	0.021317	0.050894	-0.023182
+4.483414	-0.105338	-0.368683	9.834729	0.019718	0.051028	-0.022250
+4.484416	-0.105338	-0.411775	9.810788	0.019319	0.050495	-0.023715
+4.485500	-0.110126	-0.399805	9.777271	0.020118	0.050628	-0.023315
+4.486500	-0.146037	-0.414169	9.810788	0.020518	0.050761	-0.023582
+4.487440	-0.162795	-0.423746	9.760513	0.020251	0.051161	-0.022783
+4.488418	-0.210676	-0.464444	9.782060	0.020384	0.052093	-0.022116
+4.489344	-0.153219	-0.459656	9.774877	0.020518	0.051827	-0.021717
+4.490368	-0.105338	-0.471626	9.837123	0.019452	0.050628	-0.022116
+4.491353	-0.095762	-0.395017	9.710238	0.019052	0.049828	-0.023982
+4.492425	-0.136460	-0.390229	9.671934	0.018786	0.050361	-0.024248
+4.493365	-0.134066	-0.406987	9.753331	0.020118	0.050628	-0.021983
+4.494366	-0.122096	-0.387835	9.803606	0.021184	0.050361	-0.022783
+4.495366	-0.124490	-0.423746	9.808394	0.020917	0.051427	-0.024248
+4.496352	-0.098156	-0.438110	9.760513	0.020384	0.050495	-0.022383
+4.497344	-0.201100	-0.447686	9.777271	0.019851	0.049828	-0.022516
+4.498341	-0.160401	-0.411775	9.774877	0.019985	0.050894	-0.022250
+4.499341	-0.201100	-0.399805	9.707844	0.019985	0.049828	-0.022383
+4.500341	-0.155613	-0.356712	9.715026	0.020384	0.050495	-0.023049
+4.501348	-0.071821	-0.404593	9.772483	0.019718	0.051161	-0.023982
+4.502396	-0.114914	-0.450080	9.762907	0.020917	0.051560	-0.022649
+4.503427	-0.165189	-0.438110	9.719814	0.020784	0.050894	-0.021051
+4.504327	-0.184341	-0.397411	9.755725	0.020784	0.051161	-0.022116
+4.505427	-0.155613	-0.366289	9.815576	0.021850	0.050894	-0.021317
+4.506424	-0.150825	-0.368683	9.808394	0.020518	0.049828	-0.021450
+4.507423	-0.143643	-0.383047	9.822758	0.020917	0.050228	-0.022250
+4.508424	-0.162795	-0.414169	9.813182	0.020651	0.050761	-0.022649
+4.509426	-0.217858	-0.418958	9.693480	0.019585	0.050894	-0.022649
+4.510379	-0.186735	-0.409381	9.731785	0.019985	0.048363	-0.022916
+4.511420	-0.150825	-0.438110	9.801212	0.020518	0.048230	-0.022783
+4.512424	-0.162795	-0.383047	9.825152	0.019851	0.050095	-0.022916
+4.513335	-0.198706	-0.416563	9.786848	0.020118	0.050228	-0.023182
+4.514341	-0.167583	-0.404593	9.779666	0.020651	0.050095	-0.023582
+4.515342	-0.153219	-0.416563	9.770089	0.020251	0.049695	-0.023982
+4.516341	-0.138854	-0.409381	9.736573	0.020384	0.049296	-0.022649
+4.517331	-0.146037	-0.409381	9.738967	0.019585	0.047830	-0.021850
+4.518330	-0.184341	-0.423746	9.786848	0.019052	0.049296	-0.022649
+4.519330	-0.196312	-0.406987	9.717420	0.021051	0.049962	-0.022250
+4.520412	-0.193917	-0.418958	9.791636	0.022116	0.049429	-0.020784
+4.521369	-0.153219	-0.411775	9.820364	0.020784	0.048896	-0.021184
+4.522408	-0.136460	-0.390229	9.774877	0.018919	0.049029	-0.021184
+4.523411	-0.138854	-0.356712	9.774877	0.018786	0.049828	-0.021184
+4.524413	-0.153219	-0.438110	9.794030	0.019052	0.050095	-0.020651
+4.525414	-0.148431	-0.454868	9.827546	0.020118	0.049828	-0.023582
+4.526411	-0.162795	-0.387835	9.774877	0.020651	0.051028	-0.024248
+4.527411	-0.158007	-0.409381	9.753331	0.020384	0.051960	-0.022116
+4.528411	-0.193917	-0.404593	9.791636	0.019985	0.051960	-0.021317
+4.529327	-0.131672	-0.342348	9.853881	0.020384	0.050628	-0.021850
+4.530328	-0.100550	-0.397411	9.801212	0.020384	0.050361	-0.022783
+4.531315	-0.134066	-0.387835	9.825152	0.020651	0.050495	-0.021583
+4.532330	-0.126884	-0.383047	9.837123	0.020784	0.050628	-0.019851
+4.533405	-0.100550	-0.411775	9.829940	0.020917	0.051960	-0.020118
+4.534397	-0.112520	-0.392623	9.719814	0.020118	0.051427	-0.021717
+4.535487	-0.102944	-0.406987	9.715026	0.020518	0.049962	-0.022516
+4.536413	-0.189129	-0.385441	9.719814	0.021051	0.049562	-0.021583
+4.537361	-0.160401	-0.414169	9.755725	0.020651	0.050095	-0.020518
+4.538354	-0.129278	-0.404593	9.846699	0.020384	0.050095	-0.019985
+4.539412	-0.124490	-0.426140	9.815576	0.019985	0.050228	-0.021717
+4.540343	-0.146037	-0.450080	9.719814	0.019718	0.051294	-0.021983
+4.541337	-0.112520	-0.438110	9.777271	0.019585	0.052227	-0.021317
+4.542331	-0.105338	-0.421352	9.803606	0.019052	0.051028	-0.022649
+4.543405	-0.112520	-0.411775	9.798818	0.020384	0.049962	-0.023049
+4.544411	-0.112520	-0.438110	9.817970	0.021850	0.050361	-0.022116
+4.545342	-0.110126	-0.418958	9.834729	0.023182	0.051560	-0.022250
+4.546363	-0.126884	-0.440504	9.750937	0.021583	0.052360	-0.022516
+4.547321	-0.172371	-0.435716	9.703056	0.020118	0.051028	-0.023449
+4.548329	-0.169977	-0.438110	9.691086	0.019851	0.052227	-0.022383
+4.549328	-0.129278	-0.447686	9.806000	0.021317	0.052626	-0.022916
+4.550327	-0.153219	-0.423746	9.779666	0.022383	0.051294	-0.021983
+4.551324	-0.131672	-0.414169	9.772483	0.021850	0.049562	-0.021450
+4.552413	-0.110126	-0.356712	9.794030	0.021983	0.049828	-0.021983
+4.553413	-0.148431	-0.378259	9.750937	0.021717	0.050361	-0.021317
+4.554354	-0.114914	-0.397411	9.782060	0.021583	0.050628	-0.021051
+4.555413	-0.095762	-0.430928	9.770089	0.022649	0.050628	-0.021850
+4.556411	-0.131672	-0.474021	9.827546	0.021717	0.050495	-0.023049
+4.557411	-0.179553	-0.423746	9.755725	0.020518	0.049429	-0.024648
+4.558409	-0.177159	-0.395017	9.719814	0.020518	0.049962	-0.023715
+4.559410	-0.112520	-0.378259	9.762907	0.019718	0.049962	-0.023315
+4.560410	-0.141249	-0.380653	9.770089	0.019452	0.049828	-0.022516
+4.561360	-0.131672	-0.380653	9.801212	0.021317	0.050628	-0.022383
+4.562346	-0.112520	-0.426140	9.834729	0.020651	0.049828	-0.020917
+4.563329	-0.143643	-0.430928	9.806000	0.020251	0.050228	-0.021583
+4.564315	-0.143643	-0.421352	9.803606	0.021317	0.050361	-0.022916
+4.565331	-0.155613	-0.406987	9.760513	0.020917	0.049695	-0.022516
+4.566328	-0.148431	-0.411775	9.755725	0.020917	0.049296	-0.022649
+4.567321	-0.153219	-0.438110	9.722208	0.020518	0.050894	-0.022649
+4.568331	-0.155613	-0.378259	9.796424	0.021051	0.051560	-0.021850
+4.569414	-0.189129	-0.387835	9.820364	0.021717	0.050628	-0.023449
+4.570410	-0.112520	-0.416563	9.808394	0.021051	0.049695	-0.022516
+4.571409	-0.158007	-0.428534	9.750937	0.021317	0.049429	-0.023049
+4.572410	-0.193917	-0.423746	9.782060	0.021717	0.050228	-0.023715
+4.573344	-0.165189	-0.395017	9.755725	0.021184	0.051161	-0.022116
+4.574345	-0.105338	-0.414169	9.777271	0.019718	0.051294	-0.021051
+4.575378	-0.134066	-0.442898	9.784454	0.019319	0.050761	-0.019585
+4.576409	-0.129278	-0.416563	9.710238	0.020384	0.050361	-0.022649
+4.577412	-0.112520	-0.378259	9.703056	0.021184	0.049962	-0.024115
+4.578410	-0.114914	-0.402199	9.643205	0.020251	0.051960	-0.023049
+4.579410	-0.167583	-0.430928	9.691086	0.019985	0.053026	-0.020917
+4.580334	-0.126884	-0.435716	9.777271	0.020518	0.051960	-0.019585
+4.581329	-0.098156	-0.390229	9.820364	0.020917	0.050628	-0.021184
+4.582329	-0.076609	-0.418958	9.796424	0.020518	0.051427	-0.022916
+4.583329	-0.110126	-0.411775	9.758119	0.020518	0.050894	-0.023182
+4.584329	-0.141249	-0.421352	9.741361	0.020518	0.050095	-0.022516
+4.585361	-0.112520	-0.406987	9.765301	0.019851	0.048629	-0.021184
+4.586402	-0.126884	-0.347136	9.741361	0.020917	0.048763	-0.020917
+4.587410	-0.141249	-0.339954	9.760513	0.021317	0.050361	-0.023049
+4.588318	-0.148431	-0.402199	9.755725	0.021983	0.051294	-0.024381
+4.589342	-0.129278	-0.416563	9.789242	0.021850	0.050894	-0.023182
+4.590355	-0.162795	-0.435716	9.707844	0.020784	0.051294	-0.021850
+4.591344	-0.122096	-0.502749	9.779666	0.020518	0.050228	-0.021184
+4.592343	-0.110126	-0.469232	9.820364	0.020518	0.050361	-0.022516
+4.593423	-0.160401	-0.411775	9.820364	0.020518	0.050761	-0.021717
+4.594347	-0.172371	-0.454868	9.801212	0.019985	0.049429	-0.023182
+4.595344	-0.119702	-0.430928	9.829940	0.020651	0.049695	-0.022783
+4.596349	-0.088580	-0.442898	9.837123	0.020251	0.050495	-0.021983
+4.597323	-0.040699	-0.409381	9.796424	0.020651	0.050228	-0.020917
+4.598341	-0.136460	-0.411775	9.798818	0.021983	0.051427	-0.021317
+4.599336	-0.181947	-0.404593	9.758119	0.022383	0.050894	-0.023182
+4.600339	-0.102944	-0.349530	9.782060	0.020784	0.052360	-0.023182
+4.601297	-0.150825	-0.354318	9.738967	0.020518	0.052760	-0.023315
+4.602371	-0.138854	-0.404593	9.801212	0.022116	0.052493	-0.022649
+4.603375	-0.122096	-0.347136	9.779666	0.021450	0.052493	-0.021583
+4.604326	-0.079003	-0.399805	9.738967	0.020384	0.052626	-0.022116
+4.605374	-0.143643	-0.447686	9.760513	0.019585	0.051427	-0.023182
+4.606353	-0.117308	-0.466838	9.810788	0.018652	0.050628	-0.023315
+4.607382	-0.205888	-0.390229	9.808394	0.020118	0.051294	-0.021051
+4.608373	-0.153219	-0.392623	9.784454	0.020651	0.050095	-0.022516
+4.609373	-0.110126	-0.404593	9.767695	0.020118	0.050761	-0.022516
+4.610373	-0.098156	-0.462050	9.829940	0.019718	0.053559	-0.023049
+4.611373	-0.136460	-0.450080	9.820364	0.020917	0.054225	-0.023449
+4.612366	-0.141249	-0.421352	9.779666	0.021184	0.053159	-0.024515
+4.613294	-0.114914	-0.430928	9.815576	0.020917	0.051827	-0.024115
+4.614298	-0.134066	-0.447686	9.794030	0.020784	0.052227	-0.022649
+4.615294	-0.086186	-0.411775	9.782060	0.022116	0.053426	-0.022383
+4.616369	-0.119702	-0.383047	9.750937	0.022116	0.053426	-0.021450
+4.617355	-0.136460	-0.383047	9.767695	0.021850	0.053026	-0.021317
+4.618353	-0.181947	-0.404593	9.767695	0.020651	0.052493	-0.022383
+4.619373	-0.112520	-0.418958	9.777271	0.019452	0.053825	-0.022250
+4.620372	-0.105338	-0.399805	9.774877	0.019851	0.054758	-0.022649
+4.621375	-0.143643	-0.385441	9.755725	0.021450	0.054358	-0.022250
+4.622370	-0.165189	-0.402199	9.772483	0.022250	0.052493	-0.021317
+4.623371	-0.150825	-0.402199	9.834729	0.021317	0.051960	-0.021583
+4.624373	-0.138854	-0.383047	9.846699	0.020118	0.052093	-0.021450
+4.625368	-0.126884	-0.366289	9.794030	0.020917	0.052227	-0.022116
+4.626371	-0.172371	-0.332772	9.729391	0.020651	0.052093	-0.020917
+4.627319	-0.186735	-0.380653	9.767695	0.019851	0.052760	-0.021717
+4.628370	-0.136460	-0.383047	9.837123	0.021051	0.052093	-0.021317
+4.629292	-0.126884	-0.368683	9.817970	0.020384	0.050894	-0.022250
+4.630280	-0.174765	-0.387835	9.798818	0.020251	0.050761	-0.022516
+4.631278	-0.162795	-0.371077	9.762907	0.019851	0.050761	-0.021983
+4.632309	-0.153219	-0.387835	9.743755	0.019851	0.049429	-0.022649
+4.633373	-0.205888	-0.404593	9.746149	0.019585	0.049296	-0.023848
+4.634372	-0.229828	-0.438110	9.659963	0.019052	0.050095	-0.024115
+4.635369	-0.165189	-0.378259	9.734179	0.020251	0.050095	-0.022649
+4.636370	-0.098156	-0.404593	9.760513	0.020118	0.048496	-0.021051
+4.637372	-0.110126	-0.428534	9.746149	0.020118	0.049429	-0.019319
+4.638351	-0.198706	-0.457262	9.796424	0.019585	0.049562	-0.020651
+4.639326	-0.186735	-0.378259	9.772483	0.019985	0.049429	-0.022516
+4.640306	-0.112520	-0.375865	9.806000	0.020518	0.048496	-0.022516
+4.641310	-0.129278	-0.378259	9.870639	0.019985	0.049029	-0.020784
+4.642305	-0.155613	-0.395017	9.746149	0.019052	0.049162	-0.022649
+4.643373	-0.189129	-0.428534	9.774877	0.019985	0.049695	-0.021184
+4.644372	-0.184341	-0.416563	9.782060	0.020118	0.050228	-0.021850
+4.645328	-0.141249	-0.373471	9.770089	0.019452	0.048763	-0.022649
+4.646365	-0.193917	-0.435716	9.750937	0.020251	0.048363	-0.021317
+4.647300	-0.191523	-0.383047	9.755725	0.019851	0.048629	-0.021717
+4.648296	-0.205888	-0.399805	9.758119	0.020518	0.047963	-0.022916
+4.649342	-0.184341	-0.395017	9.750937	0.021051	0.048096	-0.021450
+4.650369	-0.172371	-0.359106	9.801212	0.021317	0.047830	-0.021051
+4.651364	-0.134066	-0.378259	9.892186	0.020118	0.049162	-0.023049
+4.652374	-0.189129	-0.383047	9.839517	0.019452	0.050228	-0.022516
+4.653322	-0.193917	-0.351924	9.782060	0.019052	0.050228	-0.022116
+4.654372	-0.237010	-0.438110	9.844305	0.021051	0.048896	-0.021317
+4.655312	-0.146037	-0.375865	9.904156	0.021717	0.049029	-0.021051
+4.656372	-0.105338	-0.373471	9.849093	0.020651	0.050228	-0.021983
+4.657373	-0.093368	-0.380653	9.796424	0.020518	0.050361	-0.021450
+4.658373	-0.112520	-0.380653	9.741361	0.020651	0.048896	-0.021051
+4.659372	-0.112520	-0.383047	9.755725	0.021317	0.049828	-0.021850
+4.660336	-0.131672	-0.397411	9.832334	0.021184	0.049429	-0.022516
+4.661398	-0.158007	-0.366289	9.873033	0.020917	0.049828	-0.022783
+4.662371	-0.100550	-0.373471	9.798818	0.020384	0.050495	-0.022516
+4.663293	-0.158007	-0.387835	9.750937	0.020651	0.051560	-0.021583
+4.664289	-0.110126	-0.387835	9.746149	0.021450	0.050361	-0.022250
+4.665304	-0.167583	-0.416563	9.815576	0.020784	0.049029	-0.020784
+4.666372	-0.136460	-0.354318	9.796424	0.022116	0.048230	-0.021184
+4.667371	-0.136460	-0.416563	9.822758	0.021850	0.049695	-0.022649
+4.668372	-0.148431	-0.409381	9.796424	0.021583	0.051694	-0.021450
+4.669373	-0.155613	-0.409381	9.791636	0.020384	0.052893	-0.020917
+4.670370	-0.203494	-0.414169	9.839517	0.020118	0.052626	-0.022383
+4.671377	-0.148431	-0.368683	9.774877	0.020118	0.051560	-0.022916
+4.672345	-0.114914	-0.397411	9.820364	0.020651	0.051161	-0.022649
+4.673375	-0.105338	-0.411775	9.794030	0.021317	0.051694	-0.022649
+4.674373	-0.205888	-0.409381	9.736573	0.020251	0.051161	-0.022783
+4.675372	-0.160401	-0.387835	9.762907	0.020518	0.051294	-0.021717
+4.676372	-0.146037	-0.428534	9.765301	0.020518	0.051960	-0.021317
+4.677373	-0.081397	-0.442898	9.726997	0.021317	0.052227	-0.022383
+4.678366	-0.119702	-0.421352	9.841911	0.021184	0.053159	-0.022383
+4.679372	-0.086186	-0.395017	9.837123	0.019185	0.052626	-0.021583
+4.680314	-0.179553	-0.457262	9.803606	0.019452	0.052227	-0.020784
+4.681294	-0.167583	-0.452474	9.825152	0.020251	0.051560	-0.020251
+4.682311	-0.172371	-0.454868	9.846699	0.020518	0.051960	-0.021317
+4.683355	-0.138854	-0.442898	9.798818	0.020384	0.050894	-0.021983
+4.684296	-0.136460	-0.440504	9.755725	0.020118	0.050761	-0.019851
+4.685374	-0.153219	-0.428534	9.765301	0.020118	0.051960	-0.021717
+4.686328	-0.126884	-0.390229	9.729391	0.021317	0.053026	-0.021583
+4.687309	-0.095762	-0.402199	9.782060	0.021850	0.052093	-0.019851
+4.688299	-0.138854	-0.385441	9.746149	0.021450	0.050894	-0.020784
+4.689372	-0.179553	-0.416563	9.770089	0.021717	0.051294	-0.023315
+4.690372	-0.148431	-0.399805	9.779666	0.021317	0.052360	-0.023049
+4.691373	-0.189129	-0.416563	9.719814	0.021184	0.052893	-0.020917
+4.692372	-0.143643	-0.380653	9.712632	0.020251	0.053026	-0.020118
+4.693331	-0.102944	-0.409381	9.801212	0.020784	0.052227	-0.022250
+4.694369	-0.129278	-0.426140	9.779666	0.020784	0.050761	-0.024248
+4.695372	-0.129278	-0.409381	9.803606	0.020917	0.051960	-0.024248
+4.696315	-0.150825	-0.361500	9.786848	0.020518	0.053159	-0.022649
+4.697293	-0.126884	-0.392623	9.770089	0.020118	0.052893	-0.019985
+4.698293	-0.136460	-0.385441	9.815576	0.019452	0.053026	-0.020518
+4.699368	-0.148431	-0.397411	9.825152	0.020251	0.052893	-0.020651
+4.700373	-0.131672	-0.385441	9.777271	0.021051	0.053426	-0.022783
+4.701302	-0.189129	-0.399805	9.710238	0.022116	0.053426	-0.023182
+4.702326	-0.134066	-0.411775	9.774877	0.021717	0.053026	-0.021317
+4.703325	-0.126884	-0.418958	9.822758	0.021184	0.053292	-0.022783
+4.704374	-0.141249	-0.351924	9.791636	0.020384	0.052093	-0.021983
+4.705354	-0.158007	-0.402199	9.693480	0.020917	0.052626	-0.022516
+4.706390	-0.181947	-0.462050	9.760513	0.022116	0.053426	-0.024248
+4.707374	-0.146037	-0.435716	9.784454	0.020917	0.053692	-0.025314
+4.708372	-0.090974	-0.327984	9.738967	0.020917	0.052493	-0.024115
+4.709373	-0.114914	-0.390229	9.671934	0.021051	0.052626	-0.022516
+4.710373	-0.114914	-0.383047	9.748543	0.020917	0.053692	-0.022516
+4.711373	-0.153219	-0.385441	9.731785	0.020784	0.052093	-0.022916
+4.712373	-0.153219	-0.380653	9.731785	0.021184	0.051694	-0.024248
+4.713314	-0.090974	-0.375865	9.784454	0.021317	0.052093	-0.022916
+4.714295	-0.095762	-0.387835	9.810788	0.020518	0.053825	-0.022649
+4.715294	-0.153219	-0.373471	9.808394	0.021317	0.054358	-0.023715
+4.716321	-0.210676	-0.323196	9.820364	0.021850	0.053292	-0.022783
+4.717315	-0.131672	-0.337560	9.767695	0.021184	0.052360	-0.021983
+4.718326	-0.162795	-0.347136	9.722208	0.019985	0.052760	-0.023315
+4.719355	-0.153219	-0.445292	9.827546	0.020784	0.052893	-0.024248
+4.720373	-0.146037	-0.395017	9.846699	0.021450	0.053292	-0.023982
+4.721372	-0.129278	-0.383047	9.741361	0.020784	0.052626	-0.023315
+4.722373	-0.119702	-0.416563	9.705450	0.021717	0.051028	-0.023049
+4.723372	-0.131672	-0.368683	9.734179	0.022383	0.051960	-0.023715
+4.724372	-0.112520	-0.359106	9.806000	0.022649	0.053559	-0.024115
+4.725367	-0.093368	-0.395017	9.841911	0.022916	0.054625	-0.023182
+4.726341	-0.081397	-0.445292	9.829940	0.022916	0.054092	-0.024248
+4.727366	-0.114914	-0.474021	9.784454	0.022783	0.051960	-0.024781
+4.728373	-0.114914	-0.445292	9.777271	0.022116	0.051694	-0.022383
+4.729317	-0.134066	-0.433322	9.738967	0.021450	0.051560	-0.021051
+4.730295	-0.189129	-0.392623	9.683904	0.021983	0.052626	-0.021583
+4.731285	-0.146037	-0.435716	9.858669	0.022116	0.052227	-0.023582
+4.732367	-0.138854	-0.397411	9.863457	0.021184	0.051827	-0.023315
+4.733372	-0.146037	-0.399805	9.817970	0.020784	0.051694	-0.023049
+4.734370	-0.110126	-0.428534	9.765301	0.021051	0.051827	-0.023582
+4.735371	-0.160401	-0.411775	9.772483	0.021850	0.052493	-0.023182
+4.736372	-0.143643	-0.464444	9.719814	0.021850	0.052493	-0.022250
+4.737342	-0.141249	-0.426140	9.784454	0.021583	0.052760	-0.024381
+4.738292	-0.124490	-0.347136	9.810788	0.021051	0.053292	-0.023848
+4.739371	-0.148431	-0.320802	9.796424	0.021184	0.053026	-0.023582
+4.740374	-0.155613	-0.375865	9.815576	0.021184	0.052360	-0.023049
+4.741373	-0.093368	-0.395017	9.801212	0.021850	0.051427	-0.024381
+4.742372	-0.174765	-0.397411	9.794030	0.023049	0.050095	-0.024248
+4.743367	-0.160401	-0.421352	9.729391	0.021983	0.049828	-0.024115
+4.744332	-0.153219	-0.387835	9.770089	0.021450	0.049562	-0.024648
+4.745373	-0.143643	-0.349530	9.750937	0.021184	0.049828	-0.023982
+4.746369	-0.203494	-0.366289	9.774877	0.020384	0.049296	-0.023182
+4.747294	-0.189129	-0.395017	9.746149	0.020518	0.049296	-0.023182
+4.748290	-0.169977	-0.395017	9.703056	0.021051	0.049029	-0.023049
+4.749369	-0.186735	-0.395017	9.717420	0.020251	0.048629	-0.023182
+4.750374	-0.150825	-0.426140	9.748543	0.019585	0.047830	-0.024248
+4.751367	-0.169977	-0.433322	9.803606	0.019319	0.048363	-0.024248
+4.752373	-0.172371	-0.426140	9.753331	0.020384	0.048763	-0.021850
+4.753374	-0.126884	-0.392623	9.767695	0.021184	0.048363	-0.022383
+4.754372	-0.179553	-0.430928	9.837123	0.020651	0.049296	-0.024248
+4.755322	-0.174765	-0.392623	9.767695	0.020384	0.048496	-0.023715
+4.756371	-0.210676	-0.442898	9.794030	0.019985	0.047297	-0.022383
+4.757370	-0.186735	-0.430928	9.777271	0.019985	0.047564	-0.022250
+4.758371	-0.198706	-0.423746	9.810788	0.020784	0.047963	-0.023315
+4.759335	-0.193917	-0.387835	9.806000	0.021717	0.048763	-0.025047
+4.760362	-0.158007	-0.418958	9.784454	0.021717	0.048496	-0.023582
+4.761326	-0.189129	-0.416563	9.834729	0.022383	0.047830	-0.022116
+4.762373	-0.141249	-0.399805	9.863457	0.022383	0.048096	-0.020917
+4.763304	-0.229828	-0.411775	9.786848	0.020118	0.047430	-0.021583
+4.764294	-0.201100	-0.373471	9.815576	0.019185	0.047697	-0.021450
+4.765298	-0.131672	-0.409381	9.777271	0.019452	0.047963	-0.023049
+4.766365	-0.141249	-0.399805	9.784454	0.019985	0.048629	-0.022649
+4.767371	-0.153219	-0.399805	9.863457	0.020784	0.049162	-0.021850
+4.768368	-0.162795	-0.397411	9.796424	0.020118	0.047963	-0.021184
+4.769368	-0.177159	-0.404593	9.688692	0.020518	0.046631	-0.020518
+4.770361	-0.141249	-0.435716	9.738967	0.020651	0.047564	-0.023182
+4.771390	-0.146037	-0.385441	9.772483	0.020118	0.049162	-0.022783
+4.772374	-0.134066	-0.404593	9.806000	0.020118	0.049029	-0.023315
+4.773375	-0.136460	-0.366289	9.731785	0.019851	0.049162	-0.021717
+4.774373	-0.158007	-0.438110	9.789242	0.020118	0.047430	-0.021850
+4.775371	-0.143643	-0.426140	9.784454	0.021051	0.047297	-0.021184
+4.776372	-0.131672	-0.395017	9.772483	0.020251	0.048363	-0.021184
+4.777368	-0.124490	-0.464444	9.808394	0.018519	0.049562	-0.021051
+4.778372	-0.064639	-0.428534	9.810788	0.018519	0.048896	-0.022383
+4.779373	-0.095762	-0.373471	9.743755	0.019585	0.048496	-0.023315
+4.780316	-0.155613	-0.366289	9.832334	0.019452	0.049695	-0.023582
+4.781286	-0.102944	-0.452474	9.798818	0.021051	0.050095	-0.022783
+4.782288	-0.193917	-0.454868	9.767695	0.020917	0.049296	-0.022383
+4.783375	-0.162795	-0.426140	9.851487	0.022250	0.049429	-0.022250
+4.784371	-0.179553	-0.399805	9.791636	0.021450	0.049962	-0.023315
+4.785374	-0.146037	-0.430928	9.743755	0.019985	0.049162	-0.022516
+4.786372	-0.177159	-0.438110	9.762907	0.020251	0.049296	-0.021184
+4.787373	-0.160401	-0.418958	9.841911	0.020518	0.049296	-0.021850
+4.788314	-0.081397	-0.399805	9.817970	0.020384	0.050761	-0.021850
+4.789446	-0.071821	-0.421352	9.750937	0.020518	0.050495	-0.022383
+4.790366	-0.119702	-0.397411	9.746149	0.020784	0.050095	-0.023848
+4.791349	-0.071821	-0.361500	9.786848	0.021051	0.049296	-0.021317
+4.792332	-0.110126	-0.387835	9.794030	0.021983	0.049562	-0.020384
+4.793374	-0.184341	-0.416563	9.837123	0.021850	0.049962	-0.021184
+4.794373	-0.153219	-0.435716	9.746149	0.020118	0.051028	-0.020251
+4.795373	-0.124490	-0.418958	9.782060	0.019585	0.051827	-0.021450
+4.796314	-0.191523	-0.395017	9.782060	0.019452	0.051827	-0.022383
+4.797284	-0.210676	-0.392623	9.681510	0.020651	0.051694	-0.022116
+4.798288	-0.167583	-0.385441	9.722208	0.021583	0.050495	-0.021583
+4.799372	-0.069427	-0.390229	9.801212	0.021717	0.049828	-0.022116
+4.800372	-0.100550	-0.366289	9.815576	0.020917	0.050228	-0.020651
+4.801372	-0.126884	-0.423746	9.825152	0.020784	0.050361	-0.019452
+4.802350	-0.129278	-0.430928	9.820364	0.020118	0.051427	-0.021717
+4.803351	-0.102944	-0.428534	9.782060	0.021317	0.050361	-0.022116
+4.804314	-0.129278	-0.390229	9.760513	0.022116	0.049562	-0.021583
+4.805309	-0.136460	-0.354318	9.736573	0.021983	0.050361	-0.022116
+4.806291	-0.136460	-0.418958	9.784454	0.019851	0.051960	-0.021717
+4.807289	-0.177159	-0.390229	9.717420	0.019585	0.052360	-0.022250
+4.808325	-0.153219	-0.387835	9.719814	0.020917	0.051694	-0.021051
+4.809324	-0.162795	-0.399805	9.748543	0.021717	0.051294	-0.021317
+4.810293	-0.153219	-0.356712	9.724603	0.021450	0.052093	-0.020518
+4.811373	-0.079003	-0.383047	9.700662	0.020251	0.051827	-0.020251
+4.812328	-0.131672	-0.392623	9.767695	0.020251	0.050894	-0.020518
+4.813292	-0.174765	-0.354318	9.762907	0.021051	0.051560	-0.019985
+4.814286	-0.150825	-0.409381	9.786848	0.021450	0.052227	-0.019985
+4.815289	-0.129278	-0.397411	9.817970	0.021717	0.052093	-0.021317
+4.816405	-0.119702	-0.402199	9.750937	0.021583	0.051427	-0.022383
+4.817376	-0.100550	-0.418958	9.731785	0.020784	0.053559	-0.022250
+4.818373	-0.165189	-0.373471	9.746149	0.020251	0.053159	-0.021051
+4.819374	-0.208282	-0.371077	9.772483	0.022250	0.053026	-0.021051
+4.820372	-0.217858	-0.371077	9.791636	0.021051	0.052093	-0.021983
+4.821375	-0.169977	-0.375865	9.810788	0.020518	0.051560	-0.020784
+4.822312	-0.158007	-0.414169	9.772483	0.020118	0.051427	-0.020384
+4.823368	-0.205888	-0.416563	9.784454	0.020118	0.050361	-0.020651
+4.824344	-0.172371	-0.418958	9.789242	0.020917	0.051028	-0.021317
+4.825366	-0.184341	-0.402199	9.758119	0.021184	0.052493	-0.020384
+4.826371	-0.181947	-0.371077	9.738967	0.021450	0.051560	-0.020651
+4.827372	-0.146037	-0.366289	9.734179	0.021184	0.051427	-0.021051
+4.828373	-0.141249	-0.438110	9.777271	0.019452	0.052227	-0.022116
+4.829317	-0.136460	-0.354318	9.817970	0.020251	0.051560	-0.021717
+4.830294	-0.165189	-0.380653	9.827546	0.020917	0.050761	-0.021717
+4.831293	-0.136460	-0.428534	9.782060	0.020518	0.052227	-0.022916
+4.832370	-0.143643	-0.409381	9.796424	0.018786	0.052360	-0.022916
+4.833328	-0.119702	-0.354318	9.791636	0.019319	0.053426	-0.021450
+4.834367	-0.074215	-0.416563	9.767695	0.020518	0.052360	-0.020384
+4.835380	-0.146037	-0.397411	9.786848	0.021317	0.052760	-0.020251
+4.836313	-0.158007	-0.363895	9.760513	0.021450	0.052360	-0.020917
+4.837334	-0.129278	-0.428534	9.755725	0.021583	0.051960	-0.021983
+4.838316	-0.155613	-0.416563	9.810788	0.020917	0.052493	-0.023049
+4.839371	-0.193917	-0.375865	9.772483	0.021317	0.052093	-0.023182
+4.840372	-0.150825	-0.395017	9.750937	0.019585	0.051827	-0.021583
+4.841375	-0.138854	-0.435716	9.837123	0.019185	0.051028	-0.022783
+4.842366	-0.081397	-0.435716	9.679116	0.019585	0.051960	-0.022383
+4.843372	-0.112520	-0.426140	9.671934	0.020384	0.051694	-0.023049
+4.844369	-0.129278	-0.351924	9.782060	0.021583	0.051694	-0.022116
+4.845382	-0.131672	-0.363895	9.758119	0.021717	0.052893	-0.021317
+4.846323	-0.136460	-0.399805	9.719814	0.022383	0.051560	-0.020651
+4.847295	-0.126884	-0.368683	9.712632	0.022516	0.050495	-0.020118
+4.848293	-0.086186	-0.428534	9.712632	0.020651	0.050761	-0.020917
+4.849370	-0.112520	-0.442898	9.748543	0.019718	0.051161	-0.023049
+4.850374	-0.105338	-0.438110	9.748543	0.020251	0.051827	-0.022383
+4.851341	-0.143643	-0.447686	9.798818	0.021850	0.051960	-0.021983
+4.852447	-0.114914	-0.411775	9.841911	0.022116	0.052093	-0.023182
+4.853312	-0.126884	-0.375865	9.738967	0.021983	0.052227	-0.021717
+4.854361	-0.208282	-0.440504	9.755725	0.021583	0.051960	-0.021184
+4.855328	-0.229828	-0.423746	9.806000	0.020917	0.051694	-0.022649
+4.856315	-0.155613	-0.409381	9.834729	0.020784	0.051560	-0.022383
+4.857300	-0.112520	-0.418958	9.870639	0.022116	0.051294	-0.021983
+4.858305	-0.131672	-0.390229	9.801212	0.022516	0.052360	-0.021317
+4.859323	-0.153219	-0.421352	9.791636	0.021317	0.052360	-0.020917
+4.860341	-0.160401	-0.435716	9.794030	0.020251	0.052093	-0.021583
+4.861375	-0.160401	-0.378259	9.803606	0.019718	0.051960	-0.022383
+4.862373	-0.129278	-0.371077	9.748543	0.019851	0.051028	-0.021850
+4.863296	-0.160401	-0.390229	9.806000	0.020651	0.051427	-0.023049
+4.864293	-0.124490	-0.397411	9.815576	0.020118	0.050095	-0.022116
+4.865309	-0.124490	-0.375865	9.755725	0.020251	0.051694	-0.021317
+4.866374	-0.148431	-0.371077	9.731785	0.020651	0.051960	-0.020917
+4.867373	-0.155613	-0.366289	9.726997	0.020384	0.051827	-0.022250
+4.868342	-0.169977	-0.423746	9.703056	0.020917	0.051694	-0.022783
+4.869352	-0.143643	-0.359106	9.786848	0.021450	0.051294	-0.022916
+4.870371	-0.148431	-0.332772	9.722208	0.021450	0.051294	-0.022516
+4.871372	-0.129278	-0.375865	9.760513	0.021717	0.050761	-0.022383
+4.872368	-0.177159	-0.378259	9.743755	0.021317	0.051694	-0.021983
+4.873369	-0.124490	-0.411775	9.777271	0.020384	0.052360	-0.020118
+4.874373	-0.088580	-0.380653	9.817970	0.019718	0.052760	-0.021184
+4.875372	-0.162795	-0.385441	9.719814	0.019585	0.051427	-0.020651
+4.876372	-0.158007	-0.438110	9.688692	0.020251	0.051427	-0.020917
+4.877371	-0.225040	-0.347136	9.726997	0.019452	0.051427	-0.022116
+4.878338	-0.198706	-0.371077	9.755725	0.020784	0.051694	-0.023715
+4.879370	-0.165189	-0.421352	9.815576	0.021051	0.052227	-0.023182
+4.880292	-0.148431	-0.387835	9.765301	0.022383	0.051028	-0.022250
+4.881296	-0.167583	-0.390229	9.717420	0.020784	0.050361	-0.021317
+4.882270	-0.174765	-0.361500	9.750937	0.019851	0.049828	-0.021717
+4.883369	-0.138854	-0.337560	9.695874	0.020384	0.051028	-0.022383
+4.884374	-0.138854	-0.430928	9.729391	0.020917	0.052493	-0.021983
+4.885373	-0.131672	-0.426140	9.731785	0.020384	0.051827	-0.021983
+4.886379	-0.148431	-0.347136	9.719814	0.020784	0.051694	-0.021317
+4.887371	-0.150825	-0.380653	9.753331	0.020917	0.050228	-0.023049
+4.888328	-0.119702	-0.368683	9.765301	0.020651	0.049162	-0.023182
+4.889324	-0.143643	-0.323196	9.767695	0.020118	0.049429	-0.023049
+4.890308	-0.146037	-0.387835	9.746149	0.020384	0.050761	-0.023315
+4.891331	-0.167583	-0.395017	9.803606	0.020518	0.049562	-0.022916
+4.892372	-0.179553	-0.359106	9.789242	0.021850	0.048763	-0.020384
+4.893374	-0.150825	-0.339954	9.834729	0.021983	0.050228	-0.020518
+4.894367	-0.155613	-0.375865	9.803606	0.021051	0.050628	-0.021583
+4.895371	-0.177159	-0.433322	9.832334	0.021317	0.050761	-0.022516
+4.896291	-0.186735	-0.395017	9.738967	0.020917	0.051161	-0.022250
+4.897276	-0.122096	-0.354318	9.693480	0.020251	0.050361	-0.021717
+4.898278	-0.146037	-0.371077	9.691086	0.019718	0.050228	-0.022250
+4.899274	-0.155613	-0.433322	9.798818	0.018119	0.051694	-0.021184
+4.900280	-0.177159	-0.474021	9.782060	0.019452	0.052227	-0.020651
+4.901280	-0.150825	-0.414169	9.820364	0.020384	0.051294	-0.022116
+4.902275	-0.112520	-0.409381	9.767695	0.020917	0.051161	-0.022783
+4.903279	-0.148431	-0.366289	9.755725	0.021184	0.050761	-0.023449
+4.904279	-0.112520	-0.402199	9.794030	0.021450	0.049429	-0.021184
+4.905280	-0.143643	-0.387835	9.755725	0.021051	0.049429	-0.021850
+4.906276	-0.160401	-0.316014	9.743755	0.020251	0.048896	-0.021051
+4.907279	-0.191523	-0.335166	9.774877	0.020118	0.048896	-0.019851
+4.908279	-0.129278	-0.404593	9.813182	0.021184	0.050228	-0.022783
+4.909281	-0.134066	-0.395017	9.784454	0.023049	0.051028	-0.023582
+4.910275	-0.179553	-0.380653	9.710238	0.021717	0.049296	-0.021717
+4.911275	-0.112520	-0.359106	9.755725	0.020784	0.047830	-0.021983
+4.912279	-0.143643	-0.378259	9.760513	0.020251	0.048763	-0.021450
+4.913284	-0.155613	-0.375865	9.703056	0.020384	0.049695	-0.020651
+4.914278	-0.169977	-0.378259	9.782060	0.020917	0.049296	-0.021983
+4.915293	-0.193917	-0.402199	9.738967	0.021184	0.048896	-0.021317
+4.916295	-0.102944	-0.433322	9.719814	0.021317	0.048629	-0.022116
+4.917366	-0.126884	-0.466838	9.772483	0.021717	0.048496	-0.022649
+4.918294	-0.143643	-0.418958	9.813182	0.021051	0.049562	-0.023315
+4.919295	-0.105338	-0.395017	9.796424	0.019585	0.050894	-0.022516
+4.920290	-0.076609	-0.409381	9.827546	0.020118	0.050361	-0.022116
+4.921291	-0.136460	-0.383047	9.815576	0.019052	0.050228	-0.023049
+4.922296	-0.160401	-0.406987	9.738967	0.018919	0.050095	-0.023049
+4.923295	-0.162795	-0.411775	9.815576	0.020251	0.049296	-0.023049
+4.924295	-0.136460	-0.337560	9.770089	0.021184	0.050095	-0.021717
+4.925295	-0.177159	-0.411775	9.734179	0.020651	0.051161	-0.020251
+4.926295	-0.179553	-0.395017	9.738967	0.020917	0.050894	-0.020651
+4.927296	-0.148431	-0.320802	9.772483	0.021184	0.049296	-0.021583
+4.928292	-0.165189	-0.368683	9.736573	0.019985	0.049296	-0.020917
+4.929280	-0.158007	-0.395017	9.760513	0.020651	0.050095	-0.022383
+4.930277	-0.165189	-0.416563	9.705450	0.020917	0.050361	-0.023182
+4.931367	-0.148431	-0.454868	9.738967	0.020118	0.050495	-0.023049
+4.932359	-0.095762	-0.366289	9.813182	0.019718	0.049962	-0.021583
+4.933371	-0.117308	-0.351924	9.803606	0.020651	0.049429	-0.020251
+4.934369	-0.150825	-0.375865	9.774877	0.021184	0.048896	-0.022516
+4.935370	-0.229828	-0.363895	9.726997	0.020384	0.049695	-0.023848
+4.936373	-0.138854	-0.342348	9.743755	0.020118	0.049962	-0.024648
+4.937374	-0.093368	-0.390229	9.748543	0.020384	0.049695	-0.022383
+4.938359	-0.150825	-0.457262	9.755725	0.020251	0.050495	-0.020784
+4.939373	-0.172371	-0.423746	9.762907	0.021051	0.050894	-0.021051
+4.940373	-0.107732	-0.438110	9.753331	0.021450	0.050095	-0.022783
+4.941328	-0.148431	-0.454868	9.750937	0.020917	0.050495	-0.021051
+4.942306	-0.131672	-0.411775	9.703056	0.020651	0.049162	-0.022250
+4.943338	-0.093368	-0.462050	9.681510	0.020917	0.050095	-0.022516
+4.944330	-0.167583	-0.462050	9.767695	0.019985	0.050361	-0.021717
+4.945313	-0.143643	-0.493173	9.803606	0.019985	0.050628	-0.021850
+4.946302	-0.112520	-0.459656	9.765301	0.020118	0.049962	-0.021317
+4.947285	-0.114914	-0.418958	9.746149	0.020251	0.049162	-0.021717
+4.948277	-0.167583	-0.421352	9.798818	0.021184	0.048629	-0.022783
+4.949426	-0.138854	-0.409381	9.794030	0.021317	0.050095	-0.022649
+4.950426	-0.186735	-0.411775	9.738967	0.020651	0.051694	-0.022516
+4.951425	-0.167583	-0.390229	9.853881	0.021450	0.051427	-0.022649
+4.952422	-0.102944	-0.421352	9.774877	0.021184	0.050095	-0.023182
+4.953369	-0.131672	-0.402199	9.774877	0.020251	0.048896	-0.022383
+4.954429	-0.165189	-0.426140	9.765301	0.021051	0.049296	-0.024648
+4.955423	-0.153219	-0.375865	9.796424	0.021450	0.050761	-0.023315
+4.956425	-0.143643	-0.373471	9.803606	0.020518	0.051294	-0.021850
+4.957424	-0.169977	-0.366289	9.784454	0.021051	0.050228	-0.020384
+4.958425	-0.169977	-0.450080	9.755725	0.021317	0.050628	-0.020651
+4.959421	-0.150825	-0.383047	9.770089	0.021184	0.051294	-0.021583
+4.960347	-0.162795	-0.402199	9.789242	0.019985	0.052493	-0.022516
+4.961356	-0.153219	-0.399805	9.803606	0.021184	0.050894	-0.021450
+4.962385	-0.122096	-0.390229	9.779666	0.022383	0.049162	-0.022383
+4.963325	-0.150825	-0.397411	9.772483	0.021450	0.050095	-0.023049
+4.964341	-0.146037	-0.428534	9.801212	0.020917	0.049828	-0.022783
+4.965343	-0.160401	-0.402199	9.825152	0.020251	0.049029	-0.021184
+4.966340	-0.138854	-0.390229	9.820364	0.020784	0.049562	-0.020917
+4.967341	-0.138854	-0.390229	9.734179	0.021184	0.050761	-0.022116
+4.968339	-0.165189	-0.383047	9.789242	0.020384	0.050361	-0.022783
+4.969342	-0.165189	-0.368683	9.813182	0.020118	0.051161	-0.022116
+4.970335	-0.117308	-0.418958	9.808394	0.020118	0.051827	-0.022383
+4.971334	-0.196312	-0.416563	9.770089	0.021583	0.051827	-0.022783
+4.972340	-0.172371	-0.342348	9.782060	0.021983	0.051161	-0.023049
+4.973297	-0.165189	-0.380653	9.782060	0.021450	0.052760	-0.023848
+4.974293	-0.158007	-0.430928	9.777271	0.020784	0.052493	-0.023049
+4.975293	-0.165189	-0.399805	9.779666	0.021184	0.051294	-0.022383
+4.976293	-0.155613	-0.380653	9.779666	0.020917	0.051294	-0.022516
+4.977293	-0.196312	-0.445292	9.770089	0.021184	0.051694	-0.021450
+4.978293	-0.129278	-0.428534	9.748543	0.020651	0.053292	-0.023449
+4.979293	-0.150825	-0.361500	9.779666	0.021051	0.052626	-0.023582
+4.980293	-0.143643	-0.421352	9.832334	0.021184	0.050761	-0.021983
+4.981293	-0.150825	-0.462050	9.815576	0.022116	0.050228	-0.023182
+4.982293	-0.126884	-0.395017	9.695874	0.021717	0.051294	-0.022783
+4.983293	-0.122096	-0.409381	9.722208	0.021850	0.052760	-0.021717
+4.984287	-0.129278	-0.457262	9.753331	0.021983	0.052493	-0.021717
+4.985293	-0.114914	-0.426140	9.746149	0.020784	0.051294	-0.022383
+4.986293	-0.138854	-0.378259	9.777271	0.020651	0.051960	-0.023449
+4.987304	-0.158007	-0.404593	9.798818	0.020384	0.051827	-0.022916
+4.988293	-0.076609	-0.464444	9.760513	0.021184	0.051161	-0.021583
+4.989294	-0.114914	-0.428534	9.767695	0.021317	0.050761	-0.021983
+4.990293	-0.131672	-0.418958	9.779666	0.021317	0.051294	-0.021450
+4.991293	-0.134066	-0.390229	9.736573	0.020251	0.051427	-0.021717
+4.992293	-0.076609	-0.385441	9.760513	0.021051	0.050495	-0.022383
+4.993293	-0.143643	-0.459656	9.700662	0.021583	0.050228	-0.022516
+4.994293	-0.134066	-0.402199	9.772483	0.021583	0.051427	-0.021583
+4.995289	-0.112520	-0.373471	9.810788	0.020917	0.052360	-0.022116
+4.996300	-0.122096	-0.368683	9.810788	0.020251	0.051294	-0.022250
+4.997299	-0.165189	-0.349530	9.868245	0.021184	0.050228	-0.021717
+4.998293	-0.146037	-0.402199	9.820364	0.021184	0.049029	-0.022649
+4.999294	-0.179553	-0.430928	9.791636	0.021850	0.049562	-0.023715
+5.000293	-0.150825	-0.399805	9.849093	0.021051	0.050495	-0.020784
diff --git a/src/test/data/IMU/imu_static15s.txt b/src/test/data/IMU/imu_static15s.txt
new file mode 100644
index 0000000000000000000000000000000000000000..aa36e7cfc65e45138d362b1a8b5b9e084322efe0
--- /dev/null
+++ b/src/test/data/IMU/imu_static15s.txt
@@ -0,0 +1,15002 @@
+0.000454	-0.033517	0.033517	9.789242	0.055424	0.085268	-0.034907
+0.001431	-0.052669	0.064639	9.777271	0.048496	0.085668	-0.037571
+0.002475	-0.062245	-0.028729	9.791636	0.044899	0.086600	-0.038104
+0.003526	0.004788	-0.069427	9.817970	0.047963	0.086467	-0.036372
+0.004469	-0.045487	-0.093368	9.837123	0.050761	0.088332	-0.034773
+0.005527	-0.057457	-0.090974	9.801212	0.051694	0.090597	-0.038504
+0.006527	-0.023940	-0.088580	9.741361	0.050628	0.086867	-0.036772
+0.007527	0.011970	-0.050275	9.664751	0.048629	0.084469	-0.033175
+0.008468	-0.011970	-0.076609	9.609688	0.048763	0.085268	-0.035173
+0.009459	0.028729	-0.059851	9.647993	0.047031	0.086201	-0.038104
+0.010423	0.002394	-0.047881	9.662357	0.045032	0.087400	-0.036639
+0.011433	-0.016758	-0.052669	9.729391	0.040236	0.091663	-0.034907
+0.012436	-0.059851	-0.100550	9.875427	0.041035	0.092329	-0.035573
+0.013438	0.011970	-0.086186	9.868245	0.048096	0.090064	-0.034907
+0.014433	0.004788	-0.019152	9.875427	0.052626	0.088732	-0.033175
+0.015428	0.038305	0.038305	9.794030	0.047297	0.091663	-0.035040
+0.016437	0.007182	0.009576	9.822758	0.037838	0.091796	-0.037038
+0.017461	-0.004788	-0.038305	9.901762	0.039037	0.087799	-0.038504
+0.018473	0.004788	-0.028729	10.047798	0.047031	0.086867	-0.038371
+0.019533	-0.059851	-0.002394	9.980765	0.051427	0.087533	-0.039836
+0.020466	-0.086186	0.014364	9.885003	0.050228	0.087533	-0.036106
+0.021484	-0.033517	0.019152	9.750937	0.042900	0.085801	-0.036505
+0.022496	-0.038305	0.028729	9.844305	0.040236	0.086334	-0.037038
+0.023529	-0.035911	0.009576	9.863457	0.044766	0.086334	-0.034374
+0.024526	0.050275	-0.043093	9.940066	0.048763	0.084868	-0.035573
+0.025465	0.000000	-0.045487	9.916126	0.048896	0.085135	-0.036372
+0.026457	0.002394	-0.033517	9.906550	0.049296	0.084735	-0.035839
+0.027451	-0.035911	0.000000	9.923308	0.052760	0.086467	-0.034907
+0.028457	0.062245	-0.033517	9.875427	0.053292	0.088199	-0.036905
+0.029442	0.052669	-0.026334	9.808394	0.050095	0.088332	-0.037838
+0.030531	0.043093	-0.059851	9.762907	0.049962	0.087133	-0.038237
+0.031447	0.002394	-0.047881	9.770089	0.048896	0.085934	-0.038904
+0.032424	0.043093	-0.004788	9.758119	0.048230	0.090198	-0.036772
+0.033456	0.059851	0.016758	9.724603	0.050095	0.094328	-0.036239
+0.034409	-0.002394	0.000000	9.633629	0.051028	0.092596	-0.035306
+0.035429	-0.026334	-0.028729	9.647993	0.050495	0.090331	-0.033841
+0.036502	-0.031123	-0.052669	9.664751	0.047697	0.087000	-0.034240
+0.037464	0.038305	-0.016758	9.758119	0.045432	0.088599	-0.034773
+0.038468	0.033517	-0.055063	9.738967	0.047164	0.091663	-0.035839
+0.039526	-0.028729	-0.093368	9.729391	0.047430	0.090864	-0.035040
+0.040528	-0.052669	-0.050275	9.700662	0.046897	0.086734	-0.037305
+0.041507	-0.067033	-0.007182	9.782060	0.045698	0.085934	-0.039836
+0.042530	-0.047881	-0.069427	9.772483	0.046764	0.087666	-0.034640
+0.043529	-0.023940	-0.045487	9.767695	0.048629	0.087799	-0.032908
+0.044528	-0.002394	0.002394	9.726997	0.047297	0.088466	-0.032775
+0.045461	0.033517	0.031123	9.748543	0.045032	0.088732	-0.032242
+0.046442	-0.011970	-0.033517	9.726997	0.042900	0.087666	-0.032908
+0.047522	0.038305	-0.081397	9.837123	0.047031	0.088599	-0.034773
+0.048523	0.052669	-0.026334	9.827546	0.049029	0.088865	-0.035839
+0.049455	0.011970	-0.052669	9.762907	0.049162	0.088199	-0.037305
+0.050452	-0.038305	0.028729	9.837123	0.047963	0.089798	-0.034374
+0.051421	0.028729	0.014364	9.808394	0.045432	0.090198	-0.035306
+0.052452	0.011970	-0.028729	9.774877	0.046897	0.089931	-0.033574
+0.053452	0.009576	-0.016758	9.676722	0.048363	0.091130	-0.032908
+0.054454	0.035911	0.002394	9.729391	0.046897	0.089665	-0.037305
+0.055462	0.045487	-0.004788	9.829940	0.044233	0.086334	-0.037438
+0.056463	0.019152	0.019152	9.882609	0.043167	0.089265	-0.035972
+0.057448	0.052669	0.021546	9.808394	0.045032	0.090331	-0.036905
+0.058431	0.019152	-0.026334	9.738967	0.048096	0.087933	-0.037971
+0.059492	-0.021546	-0.052669	9.798818	0.046764	0.085002	-0.036772
+0.060513	-0.050275	-0.069427	9.868245	0.045432	0.085934	-0.036372
+0.061480	-0.028729	-0.007182	9.837123	0.046231	0.086467	-0.035040
+0.062540	0.067033	-0.033517	9.949643	0.044233	0.086067	-0.034907
+0.063453	0.043093	-0.014364	9.975977	0.044233	0.087133	-0.034773
+0.064473	-0.011970	-0.011970	9.844305	0.047564	0.084335	-0.035040
+0.065502	0.002394	-0.009576	9.779666	0.047963	0.084735	-0.033841
+0.066512	-0.035911	-0.031123	9.851487	0.044632	0.086734	-0.034640
+0.067475	0.023940	-0.055063	9.784454	0.042634	0.085002	-0.034507
+0.068529	0.050275	-0.059851	9.786848	0.046631	0.083802	-0.035173
+0.069472	0.050275	-0.038305	9.753331	0.045032	0.087933	-0.035306
+0.070452	-0.033517	-0.033517	9.736573	0.045565	0.090464	-0.037038
+0.071452	-0.002394	-0.021546	9.688692	0.046231	0.089665	-0.036772
+0.072451	0.043093	-0.023940	9.619265	0.047963	0.089531	-0.033441
+0.073531	0.014364	0.007182	9.662357	0.046231	0.089398	-0.033708
+0.074442	-0.031123	0.028729	9.652781	0.043966	0.088865	-0.036239
+0.075530	-0.062245	-0.059851	9.777271	0.044899	0.087400	-0.034374
+0.076528	0.014364	-0.043093	9.758119	0.048763	0.085934	-0.033308
+0.077527	0.021546	-0.031123	9.719814	0.049429	0.087000	-0.034507
+0.078486	0.004788	0.000000	9.772483	0.048230	0.087000	-0.034507
+0.079485	0.011970	0.031123	9.707844	0.044632	0.088066	-0.035306
+0.080529	0.007182	0.014364	9.796424	0.044899	0.087266	-0.038371
+0.081532	0.004788	0.038305	9.822758	0.045565	0.087266	-0.037971
+0.082533	-0.021546	0.016758	9.896974	0.044766	0.088332	-0.036239
+0.083529	-0.033517	0.007182	9.901762	0.044899	0.087000	-0.036905
+0.084489	-0.009576	-0.026334	9.887397	0.049029	0.085135	-0.032775
+0.085476	-0.011970	-0.033517	9.829940	0.050095	0.085668	-0.033574
+0.086526	-0.021546	-0.011970	9.892186	0.049962	0.088066	-0.033574
+0.087464	0.014364	0.011970	9.918520	0.050095	0.088865	-0.038504
+0.088488	0.009576	-0.011970	9.856275	0.048629	0.087533	-0.039703
+0.089526	0.014364	-0.026334	9.858669	0.047697	0.086334	-0.035972
+0.090530	0.016758	0.028729	9.887397	0.046364	0.087133	-0.032242
+0.091528	0.023940	-0.011970	9.940066	0.049429	0.086334	-0.033841
+0.092529	0.028729	-0.004788	9.885003	0.051028	0.086201	-0.036106
+0.093529	0.004788	-0.031123	9.738967	0.048763	0.086467	-0.035173
+0.094451	0.002394	-0.002394	9.772483	0.045832	0.087133	-0.036639
+0.095444	-0.071821	-0.019152	9.770089	0.045432	0.087533	-0.037704
+0.096443	-0.009576	-0.026334	9.719814	0.043700	0.087400	-0.035306
+0.097452	0.035911	-0.019152	9.710238	0.045698	0.087666	-0.034640
+0.098536	0.004788	-0.038305	9.746149	0.046897	0.087266	-0.036639
+0.099526	-0.081397	-0.021546	9.746149	0.045432	0.085401	-0.038504
+0.100529	-0.019152	-0.047881	9.770089	0.045165	0.088466	-0.040769
+0.101472	-0.021546	-0.062245	9.717420	0.049029	0.089398	-0.035440
+0.102532	0.002394	-0.055063	9.734179	0.050228	0.089398	-0.031975
+0.103525	0.000000	-0.043093	9.813182	0.048896	0.090198	-0.034240
+0.104505	0.016758	-0.023940	9.865851	0.047164	0.088732	-0.032908
+0.105453	0.035911	-0.009576	9.801212	0.047430	0.085668	-0.036372
+0.106527	0.052669	-0.028729	9.868245	0.046364	0.086734	-0.037838
+0.107529	0.038305	-0.059851	9.798818	0.045565	0.087400	-0.037172
+0.108510	0.002394	-0.047881	9.760513	0.045432	0.087799	-0.037305
+0.109447	0.035911	-0.052669	9.731785	0.046231	0.086600	-0.035573
+0.110498	0.038305	-0.076609	9.801212	0.046631	0.087933	-0.037704
+0.111529	0.007182	-0.040699	9.901762	0.047697	0.089665	-0.035573
+0.112528	0.071821	-0.023940	9.894580	0.050761	0.090331	-0.035040
+0.113467	0.019152	-0.023940	9.827546	0.048230	0.088998	-0.035706
+0.114455	-0.031123	-0.016758	9.779666	0.047963	0.087400	-0.035706
+0.115442	-0.007182	-0.007182	9.822758	0.046098	0.086067	-0.041168
+0.116527	-0.011970	-0.052669	9.863457	0.045565	0.087133	-0.039836
+0.117463	-0.031123	-0.033517	9.837123	0.048363	0.087666	-0.036505
+0.118449	0.000000	-0.009576	9.798818	0.049162	0.086467	-0.037438
+0.119527	0.019152	0.014364	9.815576	0.049162	0.085934	-0.034507
+0.120529	0.000000	-0.004788	9.803606	0.049695	0.086734	-0.036106
+0.121531	0.016758	-0.023940	9.798818	0.050628	0.086867	-0.035040
+0.122529	0.007182	0.052669	9.839517	0.048096	0.087666	-0.035173
+0.123486	0.098156	0.023940	9.913732	0.046897	0.088466	-0.041035
+0.124479	0.014364	-0.002394	9.844305	0.045832	0.086867	-0.041035
+0.125531	0.007182	0.007182	9.868245	0.047297	0.086067	-0.036239
+0.126531	-0.009576	0.033517	9.803606	0.049429	0.088466	-0.037038
+0.127527	0.026334	0.002394	9.782060	0.046631	0.089798	-0.038504
+0.128528	0.040699	-0.007182	9.817970	0.046897	0.088066	-0.035706
+0.129490	0.059851	-0.035911	9.758119	0.045698	0.086334	-0.034907
+0.130527	0.002394	-0.021546	9.748543	0.044899	0.084868	-0.034640
+0.131470	-0.028729	-0.019152	9.796424	0.046364	0.085268	-0.037571
+0.132529	-0.038305	-0.011970	9.760513	0.047963	0.086734	-0.038504
+0.133529	-0.016758	0.004788	9.698268	0.047963	0.091796	-0.033841
+0.134524	-0.004788	-0.009576	9.731785	0.045832	0.093262	-0.033175
+0.135472	0.023940	-0.011970	9.789242	0.046631	0.089665	-0.037305
+0.136528	0.016758	0.007182	9.784454	0.046231	0.084735	-0.038104
+0.137488	-0.016758	-0.019152	9.755725	0.047697	0.083669	-0.037571
+0.138526	0.007182	-0.009576	9.688692	0.047830	0.088199	-0.036106
+0.139479	-0.007182	0.023940	9.738967	0.046897	0.091530	-0.035306
+0.140486	0.002394	-0.057457	9.801212	0.044366	0.088199	-0.033974
+0.141524	-0.007182	-0.076609	9.746149	0.046098	0.084069	-0.034374
+0.142529	0.002394	-0.035911	9.794030	0.047963	0.086734	-0.034507
+0.143525	0.033517	-0.004788	9.873033	0.051161	0.088199	-0.032908
+0.144469	0.076609	-0.028729	9.885003	0.049296	0.087666	-0.035306
+0.145530	-0.004788	-0.067033	9.877821	0.048096	0.086734	-0.036106
+0.146526	-0.019152	-0.023940	9.803606	0.048230	0.087000	-0.037038
+0.147472	0.028729	0.007182	9.791636	0.047430	0.088466	-0.038504
+0.148482	-0.016758	-0.064639	9.863457	0.044499	0.089132	-0.037971
+0.149499	-0.019152	-0.019152	9.817970	0.042501	0.088599	-0.036905
+0.150531	-0.023940	0.007182	9.834729	0.043167	0.087933	-0.035173
+0.151470	0.035911	-0.019152	9.856275	0.047164	0.088066	-0.033041
+0.152525	0.047881	0.007182	9.863457	0.046098	0.086467	-0.037704
+0.153527	0.007182	-0.007182	9.839517	0.044366	0.088599	-0.038770
+0.154526	0.007182	0.014364	9.932884	0.046764	0.087666	-0.038237
+0.155525	-0.009576	0.000000	9.901762	0.048896	0.086467	-0.036639
+0.156471	0.000000	-0.011970	9.841911	0.049162	0.085668	-0.037704
+0.157519	-0.038305	-0.004788	9.858669	0.045832	0.085934	-0.038104
+0.158528	0.007182	-0.007182	9.822758	0.046498	0.085268	-0.034240
+0.159434	-0.007182	-0.043093	9.734179	0.047031	0.084202	-0.033041
+0.160445	-0.023940	-0.052669	9.729391	0.045965	0.086867	-0.036372
+0.161445	0.019152	-0.009576	9.808394	0.046897	0.088732	-0.039170
+0.162526	0.031123	0.002394	9.832334	0.046231	0.089931	-0.037571
+0.163524	-0.021546	-0.047881	9.885003	0.046631	0.086600	-0.035173
+0.164468	-0.023940	-0.004788	9.822758	0.046897	0.084735	-0.033308
+0.165484	0.021546	0.028729	9.813182	0.046364	0.085401	-0.035706
+0.166487	0.050275	0.002394	9.779666	0.046764	0.088466	-0.032642
+0.167523	0.016758	0.026334	9.750937	0.046631	0.088199	-0.032775
+0.168480	0.019152	-0.023940	9.772483	0.048363	0.091130	-0.038237
+0.169529	0.021546	0.028729	9.832334	0.049562	0.092462	-0.037704
+0.170529	0.000000	-0.002394	9.825152	0.049162	0.087133	-0.036772
+0.171525	0.033517	-0.021546	9.803606	0.047697	0.084335	-0.036239
+0.172525	0.016758	-0.002394	9.839517	0.046897	0.087400	-0.037971
+0.173524	0.019152	0.009576	9.791636	0.048096	0.088199	-0.037305
+0.174476	0.002394	-0.016758	9.762907	0.047297	0.087933	-0.034107
+0.175524	0.026334	-0.016758	9.738967	0.046764	0.090064	-0.034107
+0.176525	0.038305	-0.035911	9.765301	0.048496	0.089531	-0.036106
+0.177526	0.000000	-0.004788	9.863457	0.047031	0.086467	-0.036905
+0.178525	0.031123	-0.011970	9.786848	0.047830	0.085268	-0.034374
+0.179525	0.050275	-0.040699	9.753331	0.048496	0.086600	-0.036772
+0.180524	0.026334	-0.055063	9.803606	0.048363	0.087799	-0.036372
+0.181526	0.004788	-0.016758	9.829940	0.047297	0.090464	-0.035839
+0.182479	0.043093	-0.067033	9.808394	0.045565	0.090730	-0.033708
+0.183516	0.014364	-0.021546	9.873033	0.045432	0.089265	-0.034240
+0.184524	-0.023940	-0.031123	9.853881	0.045565	0.087400	-0.038504
+0.185444	0.000000	-0.011970	9.798818	0.046098	0.086334	-0.036639
+0.186459	0.038305	-0.009576	9.803606	0.047297	0.088199	-0.033574
+0.187429	0.002394	-0.098156	9.782060	0.046498	0.087933	-0.037438
+0.188458	-0.031123	-0.067033	9.719814	0.045565	0.087000	-0.037838
+0.189525	0.000000	-0.002394	9.784454	0.043300	0.083936	-0.037038
+0.190528	-0.007182	0.009576	9.746149	0.042368	0.086734	-0.037038
+0.191459	-0.016758	0.028729	9.734179	0.043433	0.087133	-0.036372
+0.192516	-0.033517	0.007182	9.806000	0.047564	0.085135	-0.037172
+0.193527	0.014364	-0.004788	9.798818	0.048230	0.085268	-0.037305
+0.194483	-0.014364	-0.011970	9.815576	0.048763	0.087533	-0.036905
+0.195525	-0.011970	-0.011970	9.729391	0.046231	0.086334	-0.037971
+0.196524	-0.002394	0.004788	9.774877	0.045165	0.087133	-0.035306
+0.197518	-0.057457	-0.045487	9.846699	0.046897	0.087799	-0.032775
+0.198465	0.011970	-0.043093	9.841911	0.048230	0.085801	-0.034907
+0.199528	0.047881	0.009576	9.798818	0.047697	0.082470	-0.034507
+0.200477	0.021546	0.016758	9.808394	0.047297	0.083403	-0.035306
+0.201483	-0.021546	0.014364	9.827546	0.046631	0.086334	-0.037305
+0.202529	0.026334	-0.011970	9.841911	0.046364	0.088332	-0.038637
+0.203525	0.021546	-0.088580	9.851487	0.047830	0.091263	-0.038104
+0.204524	-0.028729	-0.021546	9.817970	0.047963	0.088998	-0.037172
+0.205498	0.019152	-0.014364	9.858669	0.048496	0.084202	-0.034507
+0.206525	0.007182	0.009576	9.889792	0.048629	0.084469	-0.035040
+0.207524	0.002394	0.040699	9.935278	0.048363	0.086734	-0.036372
+0.208524	0.023940	0.016758	9.829940	0.045698	0.087400	-0.034907
+0.209447	0.011970	0.000000	9.755725	0.043700	0.085801	-0.035306
+0.210452	-0.040699	-0.031123	9.865851	0.045965	0.085002	-0.036905
+0.211457	-0.014364	0.007182	9.889792	0.048230	0.086334	-0.038371
+0.212455	-0.004788	0.011970	9.832334	0.049162	0.088865	-0.036772
+0.213451	-0.021546	-0.023940	9.755725	0.048763	0.088599	-0.036639
+0.214481	-0.002394	0.007182	9.815576	0.048763	0.089398	-0.035040
+0.215465	-0.016758	-0.038305	9.873033	0.046364	0.089132	-0.035573
+0.216459	0.023940	-0.076609	9.798818	0.044499	0.088865	-0.037704
+0.217525	-0.011970	-0.064639	9.791636	0.045165	0.089665	-0.037838
+0.218519	0.028729	-0.069427	9.837123	0.047031	0.086467	-0.038104
+0.219471	0.043093	-0.055063	9.827546	0.046098	0.089531	-0.036106
+0.220477	-0.031123	-0.023940	9.923308	0.045165	0.090597	-0.029711
+0.221477	0.023940	0.009576	9.889792	0.044366	0.087000	-0.033574
+0.222529	0.045487	-0.009576	9.885003	0.044100	0.086467	-0.037172
+0.223525	0.021546	0.016758	9.803606	0.047564	0.086201	-0.035573
+0.224525	-0.038305	-0.033517	9.782060	0.050228	0.085534	-0.033175
+0.225434	0.031123	-0.016758	9.882609	0.051028	0.087533	-0.036639
+0.226528	-0.007182	-0.055063	9.806000	0.047164	0.087266	-0.037971
+0.227524	-0.007182	-0.055063	9.806000	0.045165	0.087533	-0.035440
+0.228525	-0.043093	-0.011970	9.762907	0.046631	0.090198	-0.033175
+0.229493	0.009576	-0.043093	9.774877	0.048496	0.089132	-0.034507
+0.230483	-0.023940	-0.019152	9.760513	0.049429	0.087266	-0.038237
+0.231524	-0.011970	0.004788	9.765301	0.046897	0.087533	-0.036372
+0.232525	-0.043093	-0.016758	9.755725	0.045299	0.087933	-0.037704
+0.233500	-0.035911	-0.023940	9.743755	0.044233	0.087133	-0.039703
+0.234482	0.004788	-0.057457	9.784454	0.045299	0.084069	-0.035706
+0.235457	-0.007182	-0.026334	9.743755	0.045832	0.085268	-0.035306
+0.236451	0.031123	-0.016758	9.786848	0.044899	0.087533	-0.032642
+0.237465	0.040699	-0.007182	9.810788	0.044632	0.090464	-0.035040
+0.238525	-0.011970	-0.009576	9.734179	0.045698	0.088466	-0.036505
+0.239462	-0.014364	0.009576	9.765301	0.048363	0.086600	-0.034773
+0.240522	0.023940	-0.014364	9.753331	0.047430	0.087533	-0.034240
+0.241528	0.086186	-0.093368	9.767695	0.045965	0.086734	-0.036239
+0.242530	0.045487	-0.023940	9.782060	0.047164	0.088066	-0.037704
+0.243526	0.021546	-0.033517	9.803606	0.049562	0.089398	-0.039969
+0.244522	0.028729	-0.028729	9.755725	0.049562	0.088332	-0.037438
+0.245525	0.009576	-0.004788	9.770089	0.047830	0.087000	-0.034374
+0.246524	0.002394	0.004788	9.853881	0.045698	0.087933	-0.035040
+0.247525	0.038305	-0.026334	9.858669	0.043567	0.090331	-0.039170
+0.248437	-0.009576	-0.047881	9.743755	0.046631	0.090997	-0.038104
+0.249443	0.002394	-0.040699	9.777271	0.045165	0.087400	-0.038371
+0.250456	-0.014364	-0.040699	9.736573	0.042501	0.085534	-0.034107
+0.251524	-0.055063	-0.079003	9.770089	0.045432	0.084868	-0.030643
+0.252469	-0.052669	0.031123	9.849093	0.049562	0.086334	-0.034507
+0.253524	-0.062245	-0.004788	9.808394	0.050361	0.088199	-0.035839
+0.254524	-0.028729	-0.028729	9.801212	0.046098	0.088732	-0.033175
+0.255468	-0.014364	0.000000	9.772483	0.044899	0.087933	-0.033841
+0.256524	0.009576	-0.021546	9.798818	0.044366	0.088998	-0.035972
+0.257480	0.062245	-0.009576	9.849093	0.043034	0.088732	-0.035440
+0.258465	0.043093	-0.074215	9.894580	0.046498	0.086734	-0.035306
+0.259460	0.011970	-0.009576	9.861063	0.047564	0.088066	-0.036905
+0.260427	-0.011970	0.028729	9.794030	0.049029	0.089531	-0.040236
+0.261489	-0.019152	0.000000	9.851487	0.047697	0.088865	-0.038371
+0.262470	0.026334	-0.019152	9.798818	0.047963	0.087000	-0.038104
+0.263439	0.045487	-0.071821	9.827546	0.048629	0.087266	-0.034640
+0.264454	0.045487	-0.064639	9.861063	0.047164	0.086334	-0.034240
+0.265428	0.019152	0.002394	9.827546	0.047564	0.088332	-0.033974
+0.266427	-0.019152	-0.009576	9.863457	0.047430	0.087000	-0.037172
+0.267452	-0.014364	-0.035911	9.827546	0.045965	0.083403	-0.038770
+0.268450	-0.043093	-0.009576	9.822758	0.044233	0.085668	-0.034374
+0.269430	0.019152	0.026334	9.806000	0.043433	0.088998	-0.033041
+0.270453	0.040699	-0.031123	9.822758	0.046364	0.089931	-0.035839
+0.271452	0.009576	-0.043093	9.853881	0.048496	0.089665	-0.038504
+0.272427	0.002394	-0.043093	9.856275	0.050095	0.086067	-0.038770
+0.273428	0.000000	0.002394	9.822758	0.049695	0.082870	-0.037172
+0.274454	0.011970	0.074215	9.904156	0.048496	0.084735	-0.039037
+0.275428	-0.028729	0.002394	9.837123	0.048363	0.085801	-0.037571
+0.276452	-0.009576	0.000000	9.777271	0.045432	0.087666	-0.036905
+0.277429	0.011970	0.050275	9.801212	0.044100	0.089531	-0.036905
+0.278363	-0.011970	-0.011970	9.794030	0.047697	0.091263	-0.034507
+0.279383	0.009576	0.002394	9.851487	0.050894	0.088998	-0.036505
+0.280392	0.016758	-0.011970	9.858669	0.048496	0.085534	-0.039170
+0.281361	0.035911	-0.002394	9.825152	0.045832	0.087133	-0.037305
+0.282385	0.031123	-0.033517	9.834729	0.047830	0.089931	-0.035706
+0.283385	0.026334	-0.033517	9.861063	0.050228	0.087533	-0.036639
+0.284360	0.028729	-0.045487	9.806000	0.048896	0.086067	-0.036905
+0.285385	-0.019152	-0.035911	9.762907	0.048230	0.089132	-0.039436
+0.286386	-0.026334	0.009576	9.726997	0.048629	0.089265	-0.037438
+0.287436	0.016758	-0.011970	9.798818	0.047963	0.088732	-0.032642
+0.288460	0.028729	-0.016758	9.810788	0.050228	0.087933	-0.035173
+0.289440	0.047881	0.052669	9.710238	0.049429	0.085801	-0.036239
+0.290433	0.002394	0.043093	9.695874	0.046231	0.085534	-0.035040
+0.291384	-0.031123	-0.007182	9.789242	0.046498	0.086600	-0.035040
+0.292466	0.038305	-0.067033	9.786848	0.046631	0.087266	-0.033974
+0.293439	0.028729	-0.059851	9.738967	0.047564	0.088066	-0.036372
+0.294427	-0.050275	-0.019152	9.841911	0.045299	0.088332	-0.036772
+0.295466	-0.023940	0.035911	9.755725	0.045698	0.085268	-0.036505
+0.296439	0.033517	-0.002394	9.705450	0.047164	0.086334	-0.036639
+0.297438	0.067033	-0.011970	9.794030	0.048496	0.090198	-0.036505
+0.298408	-0.023940	0.004788	9.817970	0.046764	0.091130	-0.036239
+0.299424	-0.062245	0.011970	9.779666	0.044233	0.088865	-0.035972
+0.300404	-0.031123	0.002394	9.782060	0.043700	0.088865	-0.032375
+0.301406	-0.011970	-0.040699	9.726997	0.045565	0.086867	-0.031443
+0.302436	0.002394	-0.050275	9.688692	0.047430	0.086600	-0.036106
+0.303439	0.011970	-0.021546	9.731785	0.048629	0.089665	-0.038637
+0.304464	-0.031123	0.004788	9.734179	0.047564	0.089132	-0.037438
+0.305438	-0.011970	-0.011970	9.770089	0.047031	0.087799	-0.037438
+0.306441	0.011970	-0.028729	9.755725	0.046498	0.087666	-0.034907
+0.307464	0.000000	-0.004788	9.791636	0.045698	0.086467	-0.034773
+0.308440	-0.002394	0.021546	9.806000	0.045299	0.088332	-0.038237
+0.309382	0.038305	-0.023940	9.827546	0.047164	0.086067	-0.037305
+0.310457	0.033517	0.004788	9.806000	0.048363	0.087133	-0.037305
+0.311453	0.040699	-0.023940	9.806000	0.048363	0.088066	-0.037172
+0.312498	0.033517	0.007182	9.837123	0.044899	0.087799	-0.036239
+0.313502	0.045487	-0.002394	9.853881	0.043833	0.085668	-0.035972
+0.314454	-0.002394	0.028729	9.837123	0.045965	0.085801	-0.039037
+0.315500	0.019152	0.023940	9.817970	0.044766	0.087000	-0.041035
+0.316521	0.009576	-0.004788	9.844305	0.045165	0.087400	-0.038104
+0.317496	0.011970	-0.019152	9.846699	0.045832	0.087666	-0.035173
+0.318456	0.047881	-0.057457	9.904156	0.045432	0.088998	-0.034374
+0.319433	-0.021546	-0.045487	9.846699	0.042501	0.089798	-0.037038
+0.320429	-0.014364	-0.045487	9.779666	0.044233	0.087933	-0.039303
+0.321497	0.002394	0.009576	9.808394	0.046897	0.086201	-0.039703
+0.322527	0.000000	0.055063	9.858669	0.046098	0.086334	-0.036505
+0.323496	0.040699	0.038305	9.877821	0.046231	0.087533	-0.035573
+0.324487	0.019152	-0.019152	9.837123	0.044366	0.088466	-0.036505
+0.325438	0.023940	-0.009576	9.856275	0.043966	0.088599	-0.036772
+0.326429	-0.009576	-0.055063	9.865851	0.045165	0.088332	-0.034773
+0.327496	-0.033517	0.014364	9.820364	0.046764	0.088599	-0.035173
+0.328453	-0.026334	-0.011970	9.808394	0.049029	0.087400	-0.035706
+0.329482	-0.004788	-0.011970	9.806000	0.048896	0.087266	-0.039703
+0.330502	0.033517	-0.026334	9.880215	0.046764	0.088732	-0.039170
+0.331496	-0.021546	-0.043093	9.885003	0.046098	0.087666	-0.037571
+0.332498	0.055063	-0.026334	9.801212	0.048096	0.085401	-0.035972
+0.333497	0.004788	0.011970	9.849093	0.048763	0.088466	-0.036372
+0.334495	0.002394	0.021546	9.944854	0.047430	0.091663	-0.038237
+0.335432	-0.035911	-0.002394	9.870639	0.048096	0.089531	-0.035972
+0.336497	0.002394	-0.028729	9.774877	0.049296	0.088599	-0.037305
+0.337450	0.057457	-0.028729	9.755725	0.046364	0.089265	-0.037838
+0.338495	0.047881	-0.031123	9.829940	0.045965	0.089665	-0.035040
+0.339497	0.062245	-0.016758	9.834729	0.047164	0.088199	-0.034907
+0.340459	0.016758	-0.002394	9.844305	0.048496	0.089132	-0.034507
+0.341497	-0.009576	0.050275	9.822758	0.046764	0.088732	-0.035306
+0.342500	-0.004788	0.076609	9.770089	0.046631	0.086334	-0.039037
+0.343497	0.011970	-0.007182	9.722208	0.046631	0.086201	-0.035839
+0.344436	-0.033517	-0.055063	9.765301	0.047164	0.086467	-0.035306
+0.345466	-0.026334	-0.045487	9.829940	0.047564	0.088199	-0.037971
+0.346454	-0.019152	-0.016758	9.846699	0.047830	0.086867	-0.036239
+0.347497	-0.043093	0.035911	9.846699	0.047830	0.085401	-0.035440
+0.348495	-0.023940	-0.016758	9.829940	0.047031	0.087400	-0.034507
+0.349496	0.026334	-0.035911	9.798818	0.047430	0.088998	-0.039436
+0.350433	0.081397	-0.059851	9.815576	0.048096	0.089798	-0.041168
+0.351497	0.033517	-0.028729	9.810788	0.048096	0.086734	-0.037038
+0.352496	-0.026334	-0.019152	9.798818	0.046364	0.087000	-0.034907
+0.353498	-0.035911	-0.026334	9.832334	0.046231	0.088332	-0.038637
+0.354457	-0.011970	0.028729	9.813182	0.047963	0.084602	-0.039836
+0.355449	-0.021546	0.028729	9.849093	0.049695	0.085268	-0.034640
+0.356498	0.014364	-0.023940	9.806000	0.047697	0.085401	-0.034507
+0.357498	-0.004788	-0.074215	9.784454	0.046498	0.085268	-0.040369
+0.358501	-0.047881	-0.031123	9.798818	0.045965	0.088066	-0.041035
+0.359428	0.002394	-0.047881	9.789242	0.045432	0.088865	-0.039037
+0.360433	0.043093	-0.069427	9.839517	0.049695	0.088732	-0.039969
+0.361454	0.019152	-0.055063	9.791636	0.048629	0.088066	-0.039303
+0.362496	0.067033	0.000000	9.779666	0.047697	0.089665	-0.037438
+0.363450	-0.002394	-0.067033	9.820364	0.045832	0.090198	-0.037172
+0.364437	0.000000	-0.038305	9.820364	0.046231	0.090198	-0.036772
+0.365500	-0.028729	-0.057457	9.832334	0.049562	0.089665	-0.035173
+0.366427	-0.033517	-0.043093	9.868245	0.049695	0.088998	-0.036905
+0.367497	0.045487	-0.040699	9.853881	0.049429	0.088732	-0.038770
+0.368452	0.002394	0.007182	9.853881	0.048496	0.087266	-0.037838
+0.369499	0.021546	0.023940	9.820364	0.048496	0.084202	-0.037971
+0.370497	0.014364	0.002394	9.856275	0.049429	0.085135	-0.037571
+0.371497	0.090974	0.002394	9.861063	0.050361	0.087000	-0.036772
+0.372457	0.043093	0.043093	9.935278	0.050495	0.085401	-0.034640
+0.373451	-0.026334	0.011970	9.839517	0.049429	0.084335	-0.035706
+0.374429	0.019152	-0.023940	9.700662	0.046631	0.084602	-0.034240
+0.375425	-0.007182	-0.059851	9.750937	0.045032	0.086334	-0.034374
+0.376452	-0.007182	-0.059851	9.724603	0.046498	0.086867	-0.031709
+0.377426	-0.019152	0.028729	9.691086	0.049296	0.086600	-0.031842
+0.378425	-0.014364	0.000000	9.748543	0.049828	0.088199	-0.037305
+0.379438	-0.023940	0.016758	9.858669	0.048496	0.087000	-0.037571
+0.380435	0.004788	0.052669	9.820364	0.044899	0.087666	-0.034640
+0.381425	-0.033517	-0.009576	9.949643	0.044233	0.089132	-0.033574
+0.382425	0.011970	-0.014364	9.896974	0.049162	0.089265	-0.034374
+0.383452	-0.004788	-0.016758	9.813182	0.049429	0.089265	-0.035972
+0.384454	-0.026334	0.000000	9.743755	0.048629	0.087266	-0.035706
+0.385426	-0.064639	-0.071821	9.817970	0.047564	0.086201	-0.037438
+0.386431	0.074215	-0.047881	9.782060	0.046498	0.086867	-0.036772
+0.387440	0.050275	-0.086186	9.784454	0.048496	0.089398	-0.036505
+0.388372	0.021546	-0.043093	9.753331	0.048496	0.089531	-0.036639
+0.389387	0.047881	-0.026334	9.774877	0.048363	0.086600	-0.034773
+0.390440	0.038305	-0.026334	9.865851	0.049029	0.084735	-0.034507
+0.391440	0.009576	-0.047881	9.782060	0.047697	0.086201	-0.035839
+0.392383	-0.028729	-0.019152	9.779666	0.046098	0.087400	-0.035173
+0.393445	0.035911	0.004788	9.820364	0.046498	0.086201	-0.034640
+0.394428	0.028729	-0.002394	9.664751	0.048496	0.088998	-0.035706
+0.395459	0.011970	-0.021546	9.767695	0.048496	0.087933	-0.037438
+0.396448	-0.026334	0.011970	9.820364	0.044899	0.086467	-0.041435
+0.397444	0.033517	0.035911	9.707844	0.046364	0.088332	-0.039170
+0.398392	0.023940	0.004788	9.794030	0.047297	0.089665	-0.036505
+0.399391	0.000000	0.105338	9.839517	0.047564	0.088998	-0.035706
+0.400377	-0.004788	0.038305	9.794030	0.047430	0.089798	-0.036639
+0.401391	0.028729	-0.011970	9.837123	0.047564	0.088732	-0.038104
+0.402446	0.043093	0.004788	9.777271	0.048496	0.089265	-0.038770
+0.403443	0.014364	-0.016758	9.798818	0.048230	0.088732	-0.036905
+0.404430	0.038305	-0.007182	9.839517	0.045698	0.087666	-0.037038
+0.405442	0.028729	0.007182	9.813182	0.047430	0.086334	-0.038237
+0.406449	0.067033	-0.047881	9.856275	0.049162	0.086734	-0.037571
+0.407445	-0.009576	0.019152	9.798818	0.048896	0.087133	-0.038237
+0.408444	-0.031123	0.062245	9.703056	0.047031	0.089665	-0.038371
+0.409442	0.023940	0.009576	9.762907	0.047697	0.090064	-0.041701
+0.410446	-0.011970	-0.009576	9.822758	0.047164	0.086067	-0.040769
+0.411446	0.040699	-0.011970	9.887397	0.047830	0.085534	-0.037704
+0.412386	0.043093	-0.007182	9.853881	0.047164	0.085668	-0.034640
+0.413368	0.011970	0.004788	9.803606	0.048096	0.085668	-0.035839
+0.414447	0.031123	0.031123	9.750937	0.046764	0.088066	-0.037704
+0.415434	0.004788	-0.002394	9.748543	0.046364	0.089265	-0.037838
+0.416444	-0.007182	0.026334	9.806000	0.047564	0.089132	-0.036905
+0.417446	-0.052669	0.002394	9.849093	0.046498	0.088865	-0.037305
+0.418380	-0.035911	0.026334	9.794030	0.043034	0.087000	-0.037704
+0.419444	0.026334	-0.019152	9.839517	0.044899	0.088066	-0.035839
+0.420445	0.002394	-0.026334	9.844305	0.046498	0.089265	-0.037571
+0.421439	0.009576	-0.043093	9.913732	0.046098	0.089265	-0.037172
+0.422445	0.047881	-0.088580	9.851487	0.047564	0.087400	-0.037305
+0.423445	-0.002394	-0.016758	9.841911	0.048629	0.087533	-0.039303
+0.424384	-0.028729	-0.021546	9.875427	0.048363	0.089132	-0.040103
+0.425419	-0.021546	-0.016758	9.803606	0.047031	0.089132	-0.038637
+0.426438	0.045487	-0.026334	9.724603	0.046631	0.087933	-0.038104
+0.427446	-0.019152	-0.004788	9.762907	0.046231	0.086867	-0.034507
+0.428443	0.000000	0.023940	9.815576	0.045965	0.086734	-0.033574
+0.429446	0.055063	-0.033517	9.758119	0.048763	0.085002	-0.035573
+0.430442	0.050275	-0.011970	9.707844	0.051028	0.084335	-0.037704
+0.431445	0.026334	-0.002394	9.710238	0.047830	0.088066	-0.038637
+0.432444	0.062245	-0.035911	9.774877	0.045965	0.088998	-0.035040
+0.433446	0.035911	-0.038305	9.808394	0.047830	0.089132	-0.033841
+0.434413	0.093368	0.002394	9.853881	0.049162	0.088998	-0.032908
+0.435415	0.055063	-0.011970	9.870639	0.047297	0.088865	-0.034773
+0.436443	0.009576	-0.011970	9.858669	0.046498	0.087533	-0.037305
+0.437443	-0.007182	0.000000	9.789242	0.048763	0.088732	-0.036639
+0.438444	-0.040699	0.026334	9.806000	0.047564	0.088865	-0.038504
+0.439443	-0.023940	0.052669	9.777271	0.048363	0.087400	-0.037571
+0.440444	0.011970	0.033517	9.841911	0.047697	0.087400	-0.037438
+0.441450	-0.002394	-0.016758	9.841911	0.045432	0.089132	-0.039570
+0.442446	-0.011970	-0.057457	9.755725	0.045565	0.088599	-0.036239
+0.443439	-0.067033	-0.040699	9.772483	0.048496	0.088199	-0.036639
+0.444417	-0.014364	-0.045487	9.789242	0.050361	0.086201	-0.035440
+0.445397	-0.021546	-0.062245	9.755725	0.049296	0.086867	-0.035706
+0.446446	0.004788	-0.033517	9.794030	0.046498	0.084735	-0.037438
+0.447444	-0.064639	-0.004788	9.791636	0.044499	0.085934	-0.039436
+0.448444	0.021546	-0.059851	9.817970	0.045965	0.086867	-0.034640
+0.449410	0.023940	-0.062245	9.841911	0.047830	0.085934	-0.033308
+0.450371	-0.016758	-0.040699	9.750937	0.047830	0.086467	-0.033708
+0.451441	-0.007182	0.002394	9.765301	0.048230	0.088732	-0.035440
+0.452444	-0.052669	-0.009576	9.753331	0.049029	0.086467	-0.034507
+0.453446	0.016758	-0.038305	9.717420	0.047564	0.084602	-0.036106
+0.454386	0.026334	0.004788	9.784454	0.045165	0.085002	-0.036639
+0.455390	0.004788	0.000000	9.803606	0.047297	0.086734	-0.035972
+0.456447	0.038305	0.004788	9.774877	0.048096	0.088066	-0.035173
+0.457446	-0.002394	-0.014364	9.796424	0.047963	0.088998	-0.035440
+0.458445	0.000000	-0.031123	9.920914	0.044100	0.087666	-0.035040
+0.459445	0.035911	-0.026334	9.834729	0.044632	0.087000	-0.034107
+0.460384	0.007182	0.011970	9.829940	0.049562	0.087400	-0.037305
+0.461441	0.047881	0.004788	9.791636	0.051427	0.086467	-0.035573
+0.462447	0.045487	-0.016758	9.882609	0.049296	0.087666	-0.038504
+0.463446	0.016758	-0.011970	9.846699	0.047164	0.090198	-0.036905
+0.464437	-0.031123	-0.038305	9.789242	0.047830	0.087133	-0.036639
+0.465386	-0.011970	-0.035911	9.796424	0.048496	0.084735	-0.037571
+0.466443	0.019152	-0.004788	9.822758	0.047963	0.086467	-0.037838
+0.467446	-0.023940	0.007182	9.822758	0.048363	0.087933	-0.036905
+0.468445	0.002394	-0.007182	9.806000	0.047164	0.088732	-0.034640
+0.469445	-0.055063	0.033517	9.832334	0.047430	0.087666	-0.034240
+0.470449	-0.040699	0.055063	9.882609	0.046897	0.084335	-0.033441
+0.471445	-0.050275	0.000000	9.901762	0.048629	0.085268	-0.038104
+0.472446	-0.016758	-0.062245	9.849093	0.049429	0.087266	-0.038904
+0.473445	0.045487	-0.035911	9.834729	0.050761	0.089798	-0.036505
+0.474419	-0.004788	-0.016758	9.906550	0.050495	0.088332	-0.035706
+0.475422	-0.004788	0.007182	9.899368	0.048896	0.085801	-0.035573
+0.476444	0.016758	-0.052669	9.885003	0.046231	0.086467	-0.036505
+0.477444	0.026334	0.057457	9.808394	0.044233	0.088599	-0.034640
+0.478448	-0.019152	0.035911	9.784454	0.044632	0.090331	-0.035040
+0.479442	-0.021546	-0.023940	9.782060	0.047697	0.087266	-0.037305
+0.480448	0.021546	0.009576	9.731785	0.049296	0.085801	-0.037172
+0.481447	0.055063	0.011970	9.803606	0.049562	0.086600	-0.036505
+0.482442	0.052669	0.057457	9.851487	0.047963	0.087266	-0.034507
+0.483444	0.031123	0.028729	9.829940	0.047564	0.087266	-0.033175
+0.484400	0.023940	0.019152	9.779666	0.046764	0.089398	-0.034773
+0.485400	-0.052669	0.000000	9.741361	0.049162	0.089665	-0.037438
+0.486449	-0.050275	-0.002394	9.736573	0.048096	0.089132	-0.038371
+0.487445	0.040699	-0.009576	9.832334	0.045832	0.085668	-0.034507
+0.488416	0.055063	-0.043093	9.798818	0.047031	0.087933	-0.033841
+0.489450	0.067033	-0.004788	9.782060	0.046498	0.088998	-0.036772
+0.490384	0.035911	-0.004788	9.820364	0.045565	0.089265	-0.039570
+0.491380	-0.004788	0.033517	9.849093	0.047830	0.089531	-0.037172
+0.492393	0.021546	0.002394	9.822758	0.050495	0.085135	-0.034374
+0.493446	-0.045487	-0.004788	9.786848	0.050361	0.084469	-0.035173
+0.494369	-0.016758	-0.026334	9.758119	0.048629	0.086201	-0.030377
+0.495395	0.019152	-0.019152	9.841911	0.046231	0.088732	-0.032642
+0.496419	0.059851	0.026334	9.870639	0.045698	0.090064	-0.035440
+0.497384	0.031123	0.033517	9.856275	0.043700	0.088732	-0.036639
+0.498384	0.038305	0.026334	9.906550	0.047430	0.085668	-0.034907
+0.499414	-0.002394	-0.067033	9.806000	0.050361	0.085401	-0.037038
+0.500389	0.043093	-0.095762	9.784454	0.051294	0.087533	-0.040902
+0.501418	0.040699	-0.069427	9.853881	0.048496	0.089798	-0.040103
+0.502445	-0.004788	-0.016758	9.940066	0.047430	0.087266	-0.041168
+0.503440	-0.047881	-0.004788	9.858669	0.046364	0.084868	-0.038637
+0.504412	-0.002394	0.045487	9.834729	0.046098	0.085934	-0.036905
+0.505446	0.026334	-0.016758	9.803606	0.048230	0.090464	-0.036505
+0.506420	-0.002394	0.002394	9.829940	0.050095	0.090064	-0.035040
+0.507433	-0.031123	0.026334	9.789242	0.051294	0.089265	-0.034907
+0.508407	-0.079003	-0.033517	9.815576	0.048496	0.088199	-0.036639
+0.509416	-0.047881	0.016758	9.822758	0.048629	0.085401	-0.040236
+0.510418	-0.040699	-0.009576	9.810788	0.049162	0.085002	-0.039303
+0.511407	-0.055063	-0.052669	9.820364	0.048363	0.086201	-0.036239
+0.512429	0.004788	-0.026334	9.863457	0.045698	0.088066	-0.036772
+0.513431	0.000000	-0.069427	9.839517	0.046764	0.090198	-0.040502
+0.514434	0.019152	-0.043093	9.896974	0.049162	0.087000	-0.037971
+0.515428	0.021546	0.000000	9.935278	0.047830	0.088466	-0.036372
+0.516430	0.028729	-0.055063	9.832334	0.050361	0.088466	-0.036505
+0.517429	0.014364	-0.057457	9.808394	0.052227	0.090730	-0.034107
+0.518429	0.002394	-0.011970	9.734179	0.052360	0.088732	-0.033974
+0.519449	0.052669	0.021546	9.765301	0.050228	0.089132	-0.035839
+0.520498	0.086186	-0.002394	9.851487	0.049429	0.088466	-0.034374
+0.521496	-0.014364	0.000000	9.863457	0.048496	0.086467	-0.035306
+0.522434	-0.026334	0.016758	9.899368	0.050095	0.084602	-0.039303
+0.523423	-0.016758	0.011970	9.870639	0.049962	0.084202	-0.041302
+0.524442	-0.019152	-0.021546	9.887397	0.050228	0.085002	-0.039037
+0.525497	-0.011970	-0.071821	9.810788	0.049962	0.085934	-0.034240
+0.526497	-0.038305	-0.035911	9.820364	0.052227	0.088466	-0.032375
+0.527450	-0.021546	-0.009576	9.882609	0.051694	0.089798	-0.036106
+0.528492	-0.059851	-0.016758	9.889792	0.049962	0.087133	-0.037971
+0.529498	-0.009576	-0.023940	9.908944	0.049296	0.086067	-0.037038
+0.530451	0.045487	0.007182	9.908944	0.049029	0.083669	-0.035573
+0.531421	0.028729	0.000000	9.896974	0.051028	0.083802	-0.033441
+0.532423	-0.014364	-0.043093	9.856275	0.050495	0.084469	-0.038371
+0.533413	-0.064639	-0.009576	9.875427	0.048096	0.085135	-0.039303
+0.534418	0.028729	0.007182	9.822758	0.049162	0.086600	-0.035173
+0.535390	-0.035911	0.023940	9.784454	0.053292	0.087400	-0.035173
+0.536383	-0.071821	0.045487	9.789242	0.052626	0.086201	-0.036239
+0.537384	-0.028729	0.016758	9.901762	0.050894	0.084735	-0.036639
+0.538391	0.011970	0.002394	9.899368	0.050761	0.088466	-0.037172
+0.539387	0.040699	-0.021546	9.813182	0.052360	0.089798	-0.038371
+0.540384	0.026334	-0.016758	9.803606	0.052760	0.088066	-0.038504
+0.541380	0.019152	0.023940	9.822758	0.050095	0.087000	-0.036639
+0.542335	-0.007182	-0.055063	9.844305	0.049695	0.087400	-0.036905
+0.543354	0.047881	-0.014364	9.880215	0.051560	0.087933	-0.035306
+0.544348	-0.004788	0.009576	9.923308	0.055025	0.086334	-0.034907
+0.545334	0.016758	0.023940	9.837123	0.054625	0.083270	-0.035839
+0.546354	0.021546	0.026334	9.748543	0.053026	0.084069	-0.037838
+0.547357	-0.007182	0.011970	9.863457	0.053559	0.087533	-0.035040
+0.548357	0.004788	-0.021546	9.829940	0.052093	0.090331	-0.034240
+0.549366	0.059851	-0.062245	9.810788	0.051427	0.088332	-0.037038
+0.550389	0.098156	-0.050275	9.870639	0.051560	0.087400	-0.037172
+0.551383	-0.009576	0.004788	9.808394	0.052227	0.085401	-0.035839
+0.552415	-0.035911	0.086186	9.715026	0.052227	0.087266	-0.035440
+0.553376	-0.014364	0.031123	9.724603	0.051294	0.088599	-0.033175
+0.554434	-0.014364	-0.031123	9.810788	0.050761	0.090864	-0.034640
+0.555421	0.014364	-0.019152	9.820364	0.049695	0.088998	-0.035972
+0.556407	0.062245	-0.002394	9.856275	0.051294	0.088332	-0.037305
+0.557428	0.009576	0.021546	9.726997	0.052360	0.085801	-0.036639
+0.558431	0.007182	-0.028729	9.755725	0.052227	0.086734	-0.034773
+0.559423	0.004788	-0.064639	9.753331	0.051827	0.088199	-0.036106
+0.560399	0.009576	-0.047881	9.729391	0.049695	0.087400	-0.035440
+0.561430	0.002394	-0.021546	9.817970	0.050095	0.086467	-0.037305
+0.562428	-0.023940	-0.007182	9.820364	0.050495	0.086334	-0.037571
+0.563411	0.002394	-0.031123	9.734179	0.050361	0.084335	-0.038770
+0.564428	-0.014364	-0.014364	9.765301	0.049695	0.082204	-0.037838
+0.565462	-0.002394	0.021546	9.832334	0.051028	0.084735	-0.035972
+0.566515	-0.002394	0.002394	9.796424	0.048230	0.085934	-0.036106
+0.567495	-0.002394	0.021546	9.784454	0.047963	0.085934	-0.035173
+0.568503	0.045487	-0.014364	9.832334	0.049828	0.083802	-0.039170
+0.569502	0.055063	-0.007182	9.858669	0.051427	0.084868	-0.039969
+0.570494	0.007182	-0.050275	9.834729	0.049562	0.086334	-0.038504
+0.571495	0.031123	0.014364	9.837123	0.049695	0.087799	-0.032242
+0.572427	0.021546	-0.004788	9.875427	0.049562	0.086201	-0.033841
+0.573407	0.004788	0.028729	9.853881	0.048230	0.084069	-0.036372
+0.574464	0.038305	-0.004788	9.844305	0.050894	0.084868	-0.037305
+0.575499	0.040699	-0.055063	9.774877	0.053692	0.088332	-0.037038
+0.576496	0.033517	-0.007182	9.798818	0.052626	0.087666	-0.037172
+0.577496	-0.026334	0.000000	9.774877	0.054758	0.087533	-0.035573
+0.578497	0.007182	0.014364	9.789242	0.052227	0.088998	-0.035306
+0.579496	-0.040699	-0.026334	9.856275	0.047963	0.088066	-0.036106
+0.580497	-0.035911	-0.043093	9.674328	0.049562	0.088865	-0.037571
+0.581495	-0.086186	-0.064639	9.691086	0.049562	0.088466	-0.037438
+0.582455	0.009576	-0.067033	9.722208	0.050228	0.088998	-0.036372
+0.583459	0.021546	0.023940	9.837123	0.050495	0.090730	-0.035040
+0.584439	-0.028729	0.028729	9.762907	0.049962	0.088066	-0.035306
+0.585431	-0.009576	0.076609	9.777271	0.049562	0.087000	-0.036772
+0.586497	0.019152	0.026334	9.760513	0.047564	0.087799	-0.038104
+0.587496	0.000000	0.028729	9.734179	0.048496	0.084335	-0.038770
+0.588453	0.028729	-0.004788	9.717420	0.050761	0.082603	-0.039570
+0.589496	-0.023940	-0.045487	9.753331	0.051294	0.085934	-0.039303
+0.590496	0.011970	-0.047881	9.813182	0.050495	0.088732	-0.035306
+0.591424	0.047881	-0.052669	9.822758	0.052493	0.090730	-0.033974
+0.592497	-0.011970	0.011970	9.803606	0.051560	0.089531	-0.034773
+0.593496	-0.019152	-0.002394	9.803606	0.048763	0.087266	-0.035440
+0.594500	0.055063	-0.004788	9.844305	0.047164	0.087000	-0.034907
+0.595440	0.023940	0.002394	9.882609	0.049828	0.086600	-0.038104
+0.596497	0.028729	-0.038305	9.870639	0.054758	0.086067	-0.038237
+0.597495	0.057457	-0.026334	9.849093	0.053692	0.086600	-0.037704
+0.598452	-0.011970	0.009576	9.861063	0.051161	0.085801	-0.039703
+0.599413	-0.031123	-0.052669	9.853881	0.052360	0.082737	-0.036239
+0.600402	0.033517	-0.093368	9.861063	0.051028	0.084069	-0.035306
+0.601395	0.000000	-0.062245	9.837123	0.050228	0.087533	-0.035972
+0.602404	-0.004788	-0.069427	9.808394	0.052893	0.087400	-0.035306
+0.603423	-0.019152	-0.105338	9.746149	0.052493	0.086067	-0.036372
+0.604417	-0.004788	-0.002394	9.703056	0.051294	0.084202	-0.037971
+0.605422	-0.028729	-0.028729	9.686298	0.051827	0.083802	-0.038104
+0.606431	-0.007182	-0.040699	9.724603	0.049962	0.088732	-0.035706
+0.607427	-0.011970	0.007182	9.710238	0.049695	0.089798	-0.035573
+0.608428	-0.007182	-0.055063	9.612083	0.051560	0.085268	-0.038237
+0.609430	0.038305	-0.057457	9.705450	0.052093	0.085401	-0.040502
+0.610390	-0.002394	0.045487	9.698268	0.049962	0.087000	-0.035573
+0.611428	0.016758	0.002394	9.592930	0.048230	0.087799	-0.034240
+0.612422	0.014364	-0.023940	9.590536	0.046764	0.088199	-0.033841
+0.613425	0.019152	-0.004788	9.588142	0.046897	0.089398	-0.034240
+0.614434	0.021546	-0.038305	9.631235	0.048363	0.085801	-0.037838
+0.615374	0.000000	-0.033517	9.645599	0.047430	0.086201	-0.036106
+0.616498	-0.074215	-0.004788	9.643205	0.045432	0.085401	-0.036505
+0.617421	-0.004788	-0.011970	9.743755	0.046764	0.084335	-0.033175
+0.618438	0.040699	0.028729	9.798818	0.048363	0.086467	-0.033974
+0.619494	0.071821	0.069427	9.760513	0.047963	0.087533	-0.036505
+0.620450	0.031123	0.009576	9.741361	0.045698	0.087533	-0.034907
+0.621495	-0.007182	-0.016758	9.734179	0.045965	0.088865	-0.037571
+0.622429	0.079003	0.031123	9.827546	0.045565	0.089132	-0.038770
+0.623491	0.038305	0.014364	9.820364	0.046098	0.087799	-0.036505
+0.624494	-0.021546	0.023940	9.789242	0.046498	0.087000	-0.034374
+0.625496	-0.004788	0.045487	9.896974	0.046364	0.084202	-0.034507
+0.626500	0.004788	-0.004788	9.944854	0.045698	0.086734	-0.031709
+0.627495	0.019152	-0.050275	9.913732	0.048496	0.091397	-0.034507
+0.628493	0.000000	-0.033517	9.940066	0.050228	0.088732	-0.035440
+0.629493	-0.004788	0.038305	9.849093	0.051294	0.089531	-0.036505
+0.630495	0.011970	0.014364	9.841911	0.049162	0.090198	-0.038371
+0.631426	0.000000	-0.004788	9.892186	0.050495	0.091663	-0.037305
+0.632491	0.021546	0.014364	9.930490	0.049962	0.089132	-0.038237
+0.633403	0.016758	0.007182	9.856275	0.048496	0.088199	-0.035573
+0.634448	0.004788	0.004788	9.875427	0.048363	0.088066	-0.036106
+0.635410	0.047881	0.023940	9.923308	0.047430	0.088066	-0.036772
+0.636492	0.069427	-0.014364	9.779666	0.049429	0.086334	-0.035706
+0.637493	0.083792	-0.026334	9.870639	0.051560	0.088066	-0.036106
+0.638455	0.055063	0.002394	9.853881	0.049828	0.089665	-0.037704
+0.639496	0.083792	-0.028729	9.887397	0.048896	0.088332	-0.037571
+0.640439	0.021546	-0.124490	9.980765	0.044100	0.088732	-0.035440
+0.641485	0.081397	-0.160401	10.248898	0.052093	0.089665	-0.038104
+0.642497	0.086186	-0.208282	10.122014	0.067149	0.089665	-0.037704
+0.643494	0.047881	-0.052669	9.755725	0.063951	0.088199	-0.035706
+0.644493	0.031123	0.102944	9.482804	0.045965	0.087400	-0.037438
+0.645494	-0.038305	0.016758	9.561808	0.032242	0.086467	-0.039836
+0.646493	0.045487	-0.107732	9.952037	0.040236	0.085534	-0.038104
+0.647492	-0.004788	-0.138854	10.112437	0.059288	0.084868	-0.038904
+0.648492	0.028729	-0.153219	9.983159	0.063818	0.084069	-0.035440
+0.649410	0.047881	-0.007182	9.806000	0.052760	0.085668	-0.034240
+0.650383	0.009576	0.067033	9.669540	0.044100	0.085534	-0.039170
+0.651425	0.033517	-0.059851	9.849093	0.045965	0.085135	-0.040236
+0.652404	0.050275	-0.057457	9.937672	0.055957	0.088998	-0.037571
+0.653392	-0.007182	0.007182	9.726997	0.055291	0.087000	-0.036905
+0.654423	-0.038305	0.028729	9.664751	0.049029	0.086734	-0.036772
+0.655494	-0.011970	-0.011970	9.609688	0.046364	0.086600	-0.037438
+0.656493	0.035911	-0.090974	9.715026	0.053292	0.088732	-0.036772
+0.657493	0.052669	-0.014364	9.664751	0.055957	0.087266	-0.035040
+0.658494	0.076609	0.067033	9.516321	0.049429	0.085135	-0.035173
+0.659394	0.083792	0.047881	9.549837	0.042368	0.085534	-0.034507
+0.660420	0.064639	0.002394	9.760513	0.041168	0.090064	-0.033441
+0.661418	0.019152	-0.047881	9.935278	0.049695	0.091530	-0.038371
+0.662432	-0.007182	-0.031123	9.899368	0.056757	0.091263	-0.039969
+0.663559	0.002394	0.040699	9.626447	0.051028	0.086467	-0.038104
+0.664407	-0.047881	0.114914	9.549837	0.043034	0.085135	-0.036106
+0.665494	0.000000	0.059851	9.638417	0.042101	0.089531	-0.037038
+0.666449	-0.011970	-0.045487	9.686298	0.046098	0.089931	-0.035306
+0.667424	-0.007182	0.009576	9.736573	0.049695	0.089665	-0.036505
+0.668437	-0.045487	0.043093	9.664751	0.044766	0.086734	-0.037038
+0.669429	-0.067033	0.079003	9.671934	0.041835	0.085002	-0.036106
+0.670494	-0.062245	-0.009576	9.846699	0.045299	0.084868	-0.034240
+0.671492	-0.052669	0.043093	9.882609	0.050628	0.087000	-0.035173
+0.672493	-0.014364	0.028729	9.856275	0.051294	0.086734	-0.036106
+0.673397	0.009576	0.014364	9.806000	0.045565	0.086467	-0.036239
+0.674427	-0.019152	0.000000	9.796424	0.043167	0.087133	-0.033175
+0.675409	0.033517	-0.107732	9.918520	0.047697	0.087933	-0.033974
+0.676492	-0.035911	-0.102944	10.019070	0.053159	0.088066	-0.034773
+0.677493	-0.062245	-0.050275	9.810788	0.051827	0.088998	-0.032908
+0.678456	-0.002394	0.038305	9.650387	0.045698	0.088332	-0.030377
+0.679460	0.009576	0.035911	9.659963	0.041968	0.086734	-0.032242
+0.680494	0.026334	-0.026334	9.815576	0.043034	0.087400	-0.033441
+0.681432	-0.014364	-0.021546	9.885003	0.049162	0.087933	-0.036372
+0.682414	-0.040699	-0.069427	9.832334	0.050894	0.086201	-0.035972
+0.683492	-0.016758	0.007182	9.796424	0.047564	0.085534	-0.037971
+0.684503	-0.031123	0.004788	9.829940	0.044233	0.085002	-0.036505
+0.685431	0.028729	0.031123	9.832334	0.047963	0.085668	-0.035839
+0.686492	0.000000	-0.023940	9.870639	0.049562	0.089798	-0.039436
+0.687435	0.023940	-0.011970	9.832334	0.048096	0.090064	-0.039703
+0.688453	0.026334	0.007182	9.770089	0.046631	0.089398	-0.037838
+0.689493	-0.016758	0.028729	9.703056	0.047297	0.087133	-0.036772
+0.690499	0.009576	-0.038305	9.777271	0.048230	0.085801	-0.036772
+0.691495	-0.019152	0.031123	9.841911	0.048230	0.086334	-0.035440
+0.692492	-0.033517	0.050275	9.669540	0.046498	0.086467	-0.031043
+0.693495	-0.016758	0.009576	9.595324	0.045965	0.087133	-0.032908
+0.694451	0.019152	-0.011970	9.738967	0.046231	0.087000	-0.036772
+0.695494	0.035911	0.007182	9.868245	0.046897	0.086600	-0.037971
+0.696448	0.011970	0.000000	9.849093	0.052227	0.087666	-0.035440
+0.697446	0.007182	0.081397	9.774877	0.051294	0.086467	-0.037438
+0.698496	0.019152	0.076609	9.693480	0.046764	0.088865	-0.038104
+0.699493	-0.026334	0.057457	9.650387	0.045299	0.089265	-0.037971
+0.700493	-0.004788	-0.031123	9.719814	0.047297	0.088332	-0.035839
+0.701447	0.021546	-0.019152	9.767695	0.048496	0.088332	-0.036106
+0.702493	0.055063	0.019152	9.736573	0.048629	0.086867	-0.035972
+0.703450	0.064639	0.023940	9.686298	0.046098	0.085135	-0.034640
+0.704497	0.055063	0.090974	9.743755	0.043700	0.084069	-0.035706
+0.705450	0.043093	0.038305	9.798818	0.045965	0.087533	-0.038371
+0.706489	0.059851	-0.009576	9.736573	0.049429	0.087799	-0.039303
+0.707495	0.026334	0.050275	9.691086	0.049162	0.089265	-0.037571
+0.708490	0.009576	0.067033	9.640811	0.046498	0.092329	-0.037305
+0.709491	0.021546	0.009576	9.760513	0.045832	0.093795	-0.039969
+0.710485	0.019152	-0.016758	9.674328	0.047430	0.090331	-0.038104
+0.711408	0.019152	-0.004788	9.703056	0.047031	0.088466	-0.035706
+0.712491	0.000000	-0.007182	9.813182	0.047164	0.087799	-0.036372
+0.713495	-0.023940	0.028729	9.731785	0.045165	0.087133	-0.034640
+0.714447	0.009576	0.019152	9.674328	0.044766	0.091263	-0.035306
+0.715463	0.074215	-0.047881	9.712632	0.046897	0.088199	-0.038104
+0.716495	0.057457	-0.047881	9.717420	0.045832	0.087533	-0.037038
+0.717434	0.040699	-0.057457	9.846699	0.048230	0.088066	-0.034240
+0.718427	0.016758	-0.055063	9.896974	0.046231	0.087266	-0.033041
+0.719494	0.011970	-0.062245	9.853881	0.041835	0.086867	-0.034240
+0.720493	0.004788	-0.011970	9.844305	0.044632	0.088998	-0.035173
+0.721492	-0.019152	-0.031123	9.858669	0.047031	0.089798	-0.033841
+0.722494	0.026334	-0.016758	9.796424	0.043700	0.087666	-0.033175
+0.723447	0.009576	0.019152	9.846699	0.045165	0.089398	-0.033175
+0.724454	-0.007182	0.023940	9.777271	0.046231	0.091130	-0.035173
+0.725499	-0.007182	0.000000	9.858669	0.047297	0.088865	-0.038371
+0.726432	-0.028729	-0.033517	9.889792	0.046098	0.089531	-0.041035
+0.727492	-0.002394	-0.055063	9.798818	0.047564	0.090331	-0.037704
+0.728492	0.011970	-0.031123	9.870639	0.046498	0.088199	-0.034374
+0.729494	0.038305	0.023940	9.832334	0.048230	0.085934	-0.035040
+0.730493	0.045487	-0.019152	9.808394	0.046098	0.088066	-0.037038
+0.731472	-0.021546	0.057457	9.844305	0.045965	0.088998	-0.039969
+0.732436	-0.002394	0.035911	9.820364	0.048629	0.089265	-0.037305
+0.733472	0.009576	-0.059851	9.731785	0.047564	0.087933	-0.034773
+0.734495	0.035911	-0.057457	9.741361	0.046498	0.087133	-0.040369
+0.735426	-0.011970	-0.033517	9.892186	0.048230	0.086334	-0.039836
+0.736493	0.019152	-0.050275	9.794030	0.050495	0.087400	-0.035839
+0.737493	0.004788	-0.090974	9.772483	0.047564	0.088332	-0.033974
+0.738493	0.002394	0.004788	9.794030	0.045432	0.088199	-0.035706
+0.739491	-0.019152	-0.016758	9.777271	0.048896	0.089531	-0.037038
+0.740452	-0.021546	-0.040699	9.767695	0.049695	0.084735	-0.039969
+0.741456	-0.040699	0.007182	9.815576	0.047963	0.084202	-0.038104
+0.742499	-0.014364	0.002394	9.786848	0.047963	0.083669	-0.036239
+0.743494	0.035911	-0.019152	9.782060	0.047830	0.083936	-0.035173
+0.744449	0.004788	-0.016758	9.753331	0.048763	0.087000	-0.034640
+0.745492	0.000000	-0.064639	9.719814	0.048896	0.088865	-0.039703
+0.746494	0.004788	-0.035911	9.748543	0.046631	0.092729	-0.039436
+0.747452	0.019152	-0.016758	9.676722	0.046764	0.090464	-0.036239
+0.748491	0.016758	-0.045487	9.774877	0.047564	0.087799	-0.034773
+0.749461	0.045487	-0.074215	9.698268	0.048363	0.087666	-0.035173
+0.750401	0.028729	-0.076609	9.695874	0.048896	0.087266	-0.034773
+0.751490	0.062245	-0.045487	9.810788	0.048096	0.086867	-0.038904
+0.752492	0.059851	0.007182	9.801212	0.045032	0.087799	-0.036106
+0.753412	0.004788	-0.035911	9.789242	0.044366	0.088199	-0.035040
+0.754400	0.004788	-0.043093	9.741361	0.044233	0.088998	-0.036772
+0.755399	0.057457	-0.019152	9.837123	0.045299	0.086201	-0.035972
+0.756392	0.011970	0.009576	9.906550	0.046231	0.087266	-0.033175
+0.757393	0.062245	0.047881	9.839517	0.048363	0.089531	-0.033574
+0.758395	0.000000	0.019152	9.829940	0.048763	0.087266	-0.034507
+0.759393	0.000000	-0.014364	9.863457	0.046231	0.085934	-0.034907
+0.760376	0.002394	-0.009576	9.822758	0.044100	0.085135	-0.034773
+0.761407	-0.016758	0.033517	9.853881	0.044366	0.086067	-0.033841
+0.762461	0.059851	-0.009576	9.853881	0.046631	0.085135	-0.037038
+0.763493	0.047881	-0.009576	9.834729	0.049162	0.087133	-0.035839
+0.764451	0.038305	-0.023940	9.794030	0.047697	0.088599	-0.035040
+0.765491	0.026334	-0.007182	9.810788	0.046897	0.087666	-0.035440
+0.766496	0.026334	-0.043093	9.770089	0.047430	0.088066	-0.035040
+0.767493	-0.026334	-0.009576	9.856275	0.048363	0.088998	-0.037704
+0.768444	-0.002394	0.009576	9.873033	0.048763	0.088865	-0.035306
+0.769492	-0.028729	0.007182	9.906550	0.046897	0.090198	-0.034640
+0.770447	-0.007182	-0.009576	9.880215	0.046631	0.090464	-0.036905
+0.771467	0.067033	0.047881	9.901762	0.048363	0.087000	-0.036106
+0.772492	0.071821	0.009576	9.834729	0.046764	0.090730	-0.036372
+0.773491	0.038305	-0.007182	9.743755	0.045299	0.090730	-0.035573
+0.774442	-0.007182	-0.033517	9.726997	0.045832	0.088066	-0.036772
+0.775493	-0.033517	-0.023940	9.724603	0.046498	0.086867	-0.039703
+0.776449	0.002394	-0.035911	9.851487	0.047164	0.084868	-0.037838
+0.777492	0.038305	0.014364	9.863457	0.045299	0.084735	-0.034507
+0.778494	0.038305	0.055063	9.858669	0.045832	0.087000	-0.034507
+0.779446	0.033517	-0.045487	9.815576	0.047830	0.088199	-0.035573
+0.780476	-0.007182	-0.033517	9.719814	0.048763	0.086867	-0.036772
+0.781491	0.028729	-0.016758	9.798818	0.049962	0.086467	-0.033574
+0.782494	-0.026334	0.000000	9.784454	0.048896	0.087400	-0.034240
+0.783411	0.021546	-0.033517	9.722208	0.049562	0.088599	-0.035706
+0.784453	0.011970	-0.009576	9.813182	0.052227	0.088199	-0.034907
+0.785447	0.007182	0.038305	9.789242	0.048763	0.089132	-0.033841
+0.786493	-0.055063	-0.007182	9.731785	0.045432	0.087933	-0.034773
+0.787445	-0.057457	-0.002394	9.729391	0.045965	0.088599	-0.037838
+0.788448	-0.014364	0.043093	9.803606	0.048096	0.088066	-0.037038
+0.789488	0.016758	0.007182	9.820364	0.048763	0.086867	-0.036239
+0.790497	0.055063	0.009576	9.873033	0.047697	0.087133	-0.036905
+0.791494	0.031123	0.028729	9.746149	0.048230	0.086600	-0.034374
+0.792492	0.014364	0.007182	9.748543	0.045832	0.087533	-0.033308
+0.793492	-0.007182	0.057457	9.777271	0.045165	0.086467	-0.037571
+0.794428	-0.002394	0.045487	9.789242	0.046764	0.085002	-0.038104
+0.795491	-0.009576	0.023940	9.750937	0.047164	0.087000	-0.037172
+0.796429	-0.004788	-0.019152	9.798818	0.047430	0.087266	-0.034107
+0.797487	-0.007182	0.031123	9.801212	0.048763	0.085934	-0.034640
+0.798493	-0.009576	0.045487	9.853881	0.047697	0.087799	-0.034773
+0.799444	0.028729	0.023940	9.887397	0.047164	0.088466	-0.033974
+0.800490	0.007182	-0.028729	9.887397	0.047564	0.086334	-0.035173
+0.801460	-0.011970	0.016758	9.911338	0.046631	0.088199	-0.038504
+0.802492	0.019152	-0.016758	9.796424	0.045565	0.090198	-0.037305
+0.803490	-0.011970	-0.031123	9.784454	0.046764	0.091530	-0.034507
+0.804460	0.076609	-0.031123	9.837123	0.046897	0.089265	-0.036106
+0.805443	-0.004788	0.007182	9.870639	0.047430	0.087933	-0.037305
+0.806421	0.028729	-0.016758	9.815576	0.046498	0.088998	-0.037038
+0.807491	0.014364	-0.033517	9.820364	0.045965	0.088998	-0.034507
+0.808492	0.031123	-0.045487	9.798818	0.047430	0.086201	-0.036239
+0.809491	-0.002394	-0.031123	9.784454	0.047031	0.088066	-0.034374
+0.810448	-0.035911	-0.026334	9.801212	0.047430	0.090730	-0.033708
+0.811432	0.004788	-0.031123	9.806000	0.045565	0.088466	-0.036505
+0.812493	0.026334	-0.033517	9.911338	0.044632	0.085002	-0.037172
+0.813490	0.014364	-0.016758	9.837123	0.045299	0.085668	-0.034773
+0.814451	0.050275	0.009576	9.762907	0.048896	0.087799	-0.035173
+0.815448	0.059851	0.021546	9.746149	0.048496	0.090331	-0.037704
+0.816423	0.014364	0.009576	9.858669	0.049162	0.091663	-0.035440
+0.817493	0.031123	0.007182	9.896974	0.048629	0.089132	-0.036505
+0.818487	0.050275	-0.050275	9.846699	0.048096	0.087266	-0.035706
+0.819494	0.016758	-0.050275	9.772483	0.049296	0.085002	-0.032908
+0.820494	-0.047881	-0.028729	9.762907	0.047564	0.087666	-0.033175
+0.821493	-0.021546	0.009576	9.767695	0.049029	0.088199	-0.039170
+0.822493	0.033517	0.011970	9.772483	0.050495	0.088998	-0.039836
+0.823444	0.031123	0.004788	9.863457	0.049429	0.087933	-0.038104
+0.824486	0.028729	-0.002394	9.822758	0.046231	0.087266	-0.034374
+0.825500	-0.011970	-0.021546	9.755725	0.047697	0.089798	-0.036106
+0.826496	0.004788	-0.067033	9.815576	0.049828	0.088466	-0.036106
+0.827491	0.009576	-0.040699	9.762907	0.048496	0.088732	-0.035972
+0.828493	0.052669	-0.028729	9.762907	0.045165	0.088865	-0.034640
+0.829491	0.069427	0.014364	9.806000	0.045165	0.088332	-0.034640
+0.830493	0.062245	-0.047881	9.758119	0.046631	0.089531	-0.034507
+0.831450	0.047881	-0.002394	9.743755	0.045832	0.089665	-0.036372
+0.832448	0.055063	0.007182	9.762907	0.046631	0.089132	-0.036505
+0.833493	0.040699	-0.031123	9.753331	0.046498	0.088199	-0.037704
+0.834451	0.004788	-0.019152	9.825152	0.047164	0.088599	-0.039037
+0.835491	0.045487	0.023940	9.829940	0.049962	0.089398	-0.036239
+0.836470	0.055063	-0.019152	9.856275	0.050628	0.088199	-0.036239
+0.837491	-0.011970	-0.007182	9.810788	0.047297	0.088732	-0.038637
+0.838492	0.033517	0.028729	9.703056	0.044766	0.089931	-0.037172
+0.839492	0.002394	0.035911	9.705450	0.045299	0.088466	-0.035573
+0.840444	0.014364	0.043093	9.803606	0.048496	0.086067	-0.036106
+0.841467	0.026334	0.064639	9.746149	0.050761	0.088599	-0.037571
+0.842432	0.002394	0.028729	9.796424	0.049162	0.088332	-0.037038
+0.843419	-0.019152	0.016758	9.829940	0.047963	0.087000	-0.032775
+0.844419	-0.021546	-0.007182	9.791636	0.049162	0.087666	-0.031576
+0.845420	-0.033517	-0.023940	9.738967	0.047031	0.087133	-0.033574
+0.846419	-0.021546	0.009576	9.782060	0.046498	0.087933	-0.035706
+0.847418	-0.038305	-0.045487	9.844305	0.048096	0.086201	-0.037038
+0.848420	0.040699	-0.052669	9.801212	0.047564	0.085534	-0.037838
+0.849367	-0.023940	-0.023940	9.834729	0.046364	0.083802	-0.040502
+0.850395	0.009576	-0.026334	9.729391	0.045565	0.085268	-0.041435
+0.851386	0.011970	-0.028729	9.734179	0.045432	0.085268	-0.036905
+0.852387	0.019152	-0.007182	9.808394	0.045299	0.087266	-0.035573
+0.853373	-0.035911	-0.002394	9.815576	0.045832	0.091263	-0.036772
+0.854380	-0.007182	0.007182	9.755725	0.046231	0.090198	-0.036239
+0.855378	0.016758	-0.011970	9.758119	0.045698	0.088199	-0.033974
+0.856373	0.000000	-0.016758	9.791636	0.044899	0.086600	-0.035573
+0.857371	0.016758	0.028729	9.817970	0.045032	0.085135	-0.035440
+0.858377	-0.009576	0.002394	9.815576	0.045432	0.084868	-0.035839
+0.859453	-0.011970	-0.009576	9.798818	0.046631	0.086467	-0.034240
+0.860451	0.055063	-0.055063	9.825152	0.047564	0.085801	-0.032109
+0.861406	0.014364	-0.035911	9.825152	0.048363	0.087266	-0.035573
+0.862451	0.035911	0.014364	9.813182	0.046631	0.088332	-0.035972
+0.863480	0.062245	0.040699	9.777271	0.044899	0.088199	-0.038237
+0.864404	0.052669	-0.016758	9.770089	0.046764	0.089798	-0.034374
+0.865478	0.028729	-0.040699	9.784454	0.046897	0.087799	-0.036905
+0.866397	0.047881	0.021546	9.877821	0.047031	0.087933	-0.041568
+0.867433	0.026334	0.021546	9.810788	0.046098	0.087400	-0.037038
+0.868407	0.028729	-0.007182	9.760513	0.046897	0.088732	-0.036372
+0.869420	0.028729	-0.007182	9.873033	0.047031	0.091263	-0.035972
+0.870419	0.019152	-0.021546	9.870639	0.047697	0.091130	-0.034240
+0.871420	-0.016758	-0.016758	9.944854	0.047031	0.086600	-0.036239
+0.872420	0.045487	0.035911	9.873033	0.045965	0.085002	-0.036772
+0.873459	0.028729	-0.033517	9.755725	0.046364	0.086067	-0.038104
+0.874435	0.016758	0.052669	9.813182	0.047564	0.090597	-0.036905
+0.875381	0.047881	-0.011970	9.827546	0.046231	0.090864	-0.036505
+0.876396	0.026334	-0.028729	9.772483	0.046498	0.087266	-0.035839
+0.877422	-0.007182	-0.004788	9.803606	0.047963	0.087133	-0.034640
+0.878423	0.043093	-0.002394	9.746149	0.048230	0.085668	-0.033308
+0.879403	0.002394	0.011970	9.767695	0.048363	0.087799	-0.035306
+0.880364	-0.009576	0.023940	9.784454	0.048363	0.087400	-0.036639
+0.881366	-0.023940	0.007182	9.760513	0.050228	0.089132	-0.037438
+0.882361	0.009576	-0.026334	9.753331	0.049695	0.089132	-0.036639
+0.883413	0.004788	0.038305	9.765301	0.047164	0.088865	-0.032775
+0.884417	-0.011970	0.055063	9.801212	0.045965	0.087666	-0.035706
+0.885420	0.000000	0.002394	9.798818	0.047830	0.087799	-0.035839
+0.886420	0.019152	0.023940	9.791636	0.049828	0.087266	-0.036106
+0.887415	-0.004788	0.007182	9.868245	0.046764	0.086067	-0.037038
+0.888470	-0.031123	-0.069427	9.758119	0.044366	0.086867	-0.032775
+0.889485	-0.016758	-0.016758	9.717420	0.044366	0.088199	-0.035306
+0.890488	-0.040699	-0.007182	9.760513	0.046498	0.087933	-0.038504
+0.891483	0.011970	-0.045487	9.839517	0.047430	0.087666	-0.038371
+0.892483	-0.007182	-0.062245	9.930490	0.048230	0.087666	-0.039836
+0.893482	-0.045487	-0.021546	9.837123	0.048096	0.088732	-0.038770
+0.894450	-0.028729	-0.007182	9.726997	0.047963	0.087133	-0.035040
+0.895432	0.002394	-0.040699	9.681510	0.047830	0.086467	-0.034374
+0.896397	0.028729	-0.035911	9.810788	0.046897	0.087799	-0.035173
+0.897414	-0.004788	-0.050275	9.815576	0.045832	0.087133	-0.037971
+0.898481	-0.007182	-0.055063	9.853881	0.045565	0.086734	-0.035306
+0.899482	0.019152	-0.050275	9.892186	0.047031	0.088732	-0.031309
+0.900483	0.043093	-0.009576	9.772483	0.045698	0.089398	-0.033708
+0.901408	0.004788	0.021546	9.813182	0.045698	0.087133	-0.037438
+0.902484	0.016758	-0.038305	9.849093	0.045832	0.087000	-0.036505
+0.903484	-0.033517	0.011970	9.904156	0.047564	0.085934	-0.035972
+0.904403	-0.028729	0.057457	9.856275	0.045965	0.086734	-0.039836
+0.905416	-0.019152	-0.007182	9.846699	0.044766	0.088599	-0.039969
+0.906420	0.009576	-0.002394	9.829940	0.045432	0.090597	-0.037038
+0.907414	0.007182	-0.026334	9.870639	0.046364	0.090464	-0.031443
+0.908484	-0.028729	0.002394	9.746149	0.045965	0.088732	-0.033308
+0.909483	-0.035911	0.009576	9.791636	0.045432	0.085135	-0.035573
+0.910442	0.028729	-0.023940	9.782060	0.045299	0.086734	-0.033175
+0.911406	0.031123	-0.016758	9.832334	0.046498	0.086867	-0.032775
+0.912483	0.019152	0.026334	9.829940	0.045698	0.087000	-0.037704
+0.913485	-0.011970	0.002394	9.777271	0.046098	0.084868	-0.038770
+0.914487	-0.040699	-0.007182	9.822758	0.047297	0.087133	-0.039170
+0.915438	0.007182	-0.026334	9.782060	0.045299	0.087000	-0.037305
+0.916445	-0.019152	-0.040699	9.798818	0.046098	0.086201	-0.035173
+0.917418	-0.004788	0.000000	9.791636	0.046364	0.083669	-0.037438
+0.918375	-0.009576	0.033517	9.820364	0.045965	0.085668	-0.037438
+0.919373	-0.035911	0.050275	9.791636	0.048230	0.086600	-0.035440
+0.920382	-0.031123	0.028729	9.782060	0.049562	0.087400	-0.036639
+0.921382	-0.009576	-0.007182	9.801212	0.048763	0.085934	-0.037305
+0.922369	0.004788	0.040699	9.841911	0.047830	0.087666	-0.035306
+0.923483	0.047881	-0.014364	9.820364	0.047164	0.088466	-0.031443
+0.924419	0.000000	-0.031123	9.765301	0.045165	0.088998	-0.032508
+0.925442	0.002394	-0.023940	9.827546	0.044766	0.087533	-0.035706
+0.926449	0.002394	-0.057457	9.762907	0.047963	0.085534	-0.039170
+0.927485	-0.019152	0.026334	9.789242	0.047430	0.085268	-0.039436
+0.928482	0.033517	0.069427	9.817970	0.043433	0.084868	-0.038104
+0.929482	0.074215	0.038305	9.772483	0.044366	0.086734	-0.035972
+0.930412	0.055063	0.031123	9.822758	0.046098	0.088466	-0.035706
+0.931481	0.050275	0.040699	9.815576	0.047297	0.086067	-0.036106
+0.932482	0.026334	-0.019152	9.736573	0.048896	0.085934	-0.034507
+0.933437	-0.031123	0.000000	9.772483	0.049695	0.089931	-0.035573
+0.934440	-0.019152	0.014364	9.789242	0.051028	0.091130	-0.036639
+0.935421	-0.038305	0.050275	9.794030	0.046764	0.089931	-0.033841
+0.936483	-0.026334	0.011970	9.820364	0.041835	0.087933	-0.034773
+0.937483	-0.011970	-0.028729	9.829940	0.043833	0.088066	-0.038904
+0.938486	0.011970	0.000000	9.803606	0.047830	0.087000	-0.037704
+0.939437	-0.002394	0.050275	9.743755	0.050228	0.087533	-0.034107
+0.940481	0.009576	0.011970	9.806000	0.049828	0.088466	-0.032908
+0.941427	0.050275	0.035911	9.777271	0.046631	0.090331	-0.037971
+0.942435	0.055063	0.009576	9.746149	0.048629	0.088998	-0.037305
+0.943479	0.043093	0.000000	9.813182	0.048096	0.087266	-0.034640
+0.944436	-0.026334	0.002394	9.827546	0.045165	0.088466	-0.035573
+0.945482	-0.064639	-0.016758	9.777271	0.048496	0.090331	-0.037305
+0.946484	0.016758	-0.045487	9.861063	0.048363	0.090331	-0.035306
+0.947481	-0.011970	-0.057457	9.877821	0.045698	0.090730	-0.034907
+0.948482	0.000000	-0.028729	9.770089	0.046764	0.091663	-0.032775
+0.949478	0.047881	0.000000	9.770089	0.048629	0.090331	-0.036106
+0.950422	0.052669	0.004788	9.815576	0.048763	0.091130	-0.037571
+0.951438	0.007182	0.021546	9.770089	0.047164	0.092063	-0.038104
+0.952481	-0.004788	-0.038305	9.770089	0.047963	0.089665	-0.035573
+0.953486	-0.011970	-0.023940	9.813182	0.048230	0.085002	-0.036772
+0.954485	-0.002394	0.021546	9.825152	0.047297	0.085135	-0.036505
+0.955482	0.009576	0.004788	9.779666	0.047297	0.085401	-0.034907
+0.956435	0.011970	-0.016758	9.810788	0.048363	0.089398	-0.038371
+0.957482	0.007182	0.004788	9.803606	0.047830	0.089265	-0.038104
+0.958483	-0.007182	0.026334	9.849093	0.046364	0.087799	-0.038104
+0.959439	0.026334	0.040699	9.827546	0.048629	0.087799	-0.037704
+0.960416	-0.019152	0.002394	9.791636	0.049962	0.088599	-0.038237
+0.961406	-0.007182	-0.093368	9.789242	0.049162	0.087933	-0.037172
+0.962408	-0.014364	-0.035911	9.746149	0.049162	0.085002	-0.036239
+0.963421	0.000000	0.038305	9.755725	0.044499	0.084069	-0.037438
+0.964384	-0.002394	0.038305	9.750937	0.041835	0.085668	-0.037704
+0.965420	0.019152	-0.031123	9.782060	0.045299	0.090064	-0.035306
+0.966486	-0.014364	-0.023940	9.782060	0.047164	0.090597	-0.037571
+0.967482	-0.007182	-0.007182	9.808394	0.047830	0.089531	-0.036772
+0.968438	-0.011970	-0.035911	9.794030	0.049695	0.088466	-0.036372
+0.969482	-0.014364	-0.033517	9.865851	0.049962	0.089665	-0.036772
+0.970426	0.076609	-0.016758	9.870639	0.047697	0.089132	-0.038904
+0.971477	0.081397	-0.057457	9.741361	0.046364	0.085534	-0.039570
+0.972426	0.028729	-0.045487	9.700662	0.046364	0.085934	-0.035306
+0.973482	0.019152	-0.047881	9.868245	0.048496	0.088599	-0.035972
+0.974486	0.023940	-0.047881	9.760513	0.048629	0.090864	-0.038371
+0.975402	-0.007182	-0.050275	9.729391	0.044766	0.089931	-0.037838
+0.976480	-0.040699	-0.057457	9.746149	0.047164	0.089798	-0.039836
+0.977483	0.019152	-0.021546	9.770089	0.049695	0.087266	-0.036505
+0.978442	0.026334	0.011970	9.772483	0.049828	0.085534	-0.034240
+0.979458	-0.007182	-0.007182	9.815576	0.049962	0.088199	-0.033041
+0.980480	-0.021546	-0.047881	9.810788	0.046231	0.089665	-0.035440
+0.981483	0.004788	-0.033517	9.770089	0.048096	0.088732	-0.036239
+0.982386	0.021546	-0.071821	9.782060	0.048230	0.088732	-0.037172
+0.983482	-0.007182	-0.016758	9.782060	0.047164	0.085534	-0.037971
+0.984413	-0.026334	-0.035911	9.767695	0.047697	0.083669	-0.036505
+0.985415	0.000000	-0.009576	9.815576	0.047430	0.086867	-0.037038
+0.986442	0.038305	0.026334	9.789242	0.047697	0.087799	-0.036905
+0.987444	-0.007182	0.050275	9.806000	0.045165	0.087533	-0.036239
+0.988480	-0.004788	0.014364	9.806000	0.046231	0.087933	-0.037038
+0.989453	0.033517	0.016758	9.817970	0.047430	0.087933	-0.037571
+0.990484	0.002394	-0.040699	9.779666	0.048363	0.086201	-0.035573
+0.991480	0.004788	0.009576	9.715026	0.049029	0.086201	-0.035972
+0.992480	-0.045487	0.014364	9.734179	0.051028	0.087400	-0.035839
+0.993482	-0.007182	-0.014364	9.784454	0.049162	0.087266	-0.032375
+0.994445	0.031123	-0.009576	9.798818	0.046231	0.087400	-0.032109
+0.995427	0.035911	0.023940	9.796424	0.046364	0.086067	-0.037704
+0.996481	0.033517	-0.007182	9.806000	0.047963	0.086067	-0.039303
+0.997482	0.079003	0.002394	9.846699	0.050628	0.088599	-0.035706
+0.998485	0.035911	-0.028729	9.827546	0.048896	0.090198	-0.035306
+0.999417	-0.011970	0.009576	9.918520	0.048096	0.090331	-0.033974
+1.000483	0.023940	0.000000	9.901762	0.047830	0.088199	-0.033308
+1.001420	0.045487	0.007182	9.746149	0.048629	0.088599	-0.033841
+1.002424	0.043093	0.004788	9.772483	0.049029	0.090331	-0.034107
+1.003480	0.050275	0.023940	9.829940	0.049429	0.091263	-0.038904
+1.004421	0.071821	0.023940	9.801212	0.047963	0.087133	-0.037704
+1.005407	-0.002394	0.035911	9.750937	0.049296	0.088599	-0.036505
+1.006380	0.026334	0.067033	9.770089	0.046764	0.087133	-0.035839
+1.007483	0.023940	0.023940	9.801212	0.045832	0.087400	-0.036639
+1.008483	-0.014364	0.021546	9.825152	0.050228	0.090597	-0.036106
+1.009423	-0.004788	0.028729	9.901762	0.049562	0.090597	-0.040103
+1.010395	0.043093	-0.011970	9.798818	0.048363	0.086467	-0.040103
+1.011412	0.011970	-0.011970	9.741361	0.046764	0.084602	-0.035173
+1.012418	0.002394	-0.009576	9.772483	0.047297	0.085534	-0.033974
+1.013419	-0.033517	0.028729	9.774877	0.049562	0.087400	-0.037172
+1.014443	-0.059851	-0.019152	9.806000	0.048496	0.087133	-0.036239
+1.015411	0.004788	0.002394	9.719814	0.047031	0.089798	-0.037704
+1.016444	-0.014364	-0.002394	9.743755	0.046764	0.089665	-0.037838
+1.017443	-0.004788	-0.045487	9.832334	0.048363	0.090064	-0.036905
+1.018428	-0.009576	-0.019152	9.846699	0.049162	0.089665	-0.038504
+1.019482	0.043093	0.014364	9.808394	0.048230	0.088332	-0.038904
+1.020480	0.011970	-0.040699	9.729391	0.047297	0.089265	-0.038770
+1.021483	0.019152	0.023940	9.784454	0.046231	0.090198	-0.036239
+1.022483	0.057457	-0.023940	9.810788	0.046764	0.088599	-0.035839
+1.023429	0.031123	-0.045487	9.772483	0.047830	0.087799	-0.034907
+1.024482	0.007182	-0.038305	9.767695	0.047164	0.088599	-0.036372
+1.025484	0.035911	-0.002394	9.734179	0.046364	0.087933	-0.037838
+1.026451	-0.011970	0.040699	9.791636	0.048496	0.086467	-0.039037
+1.027440	0.028729	0.035911	9.767695	0.048896	0.085668	-0.035972
+1.028482	0.014364	-0.004788	9.829940	0.046098	0.089665	-0.038637
+1.029484	0.045487	-0.007182	9.856275	0.046498	0.088599	-0.039969
+1.030485	0.000000	-0.014364	9.856275	0.047697	0.087400	-0.035972
+1.031483	-0.045487	-0.038305	9.786848	0.046631	0.087933	-0.038237
+1.032484	-0.059851	-0.023940	9.829940	0.045165	0.085401	-0.038504
+1.033484	0.014364	0.014364	9.834729	0.047164	0.087799	-0.036639
+1.034394	0.043093	-0.019152	9.774877	0.048763	0.087133	-0.036239
+1.035410	0.000000	-0.026334	9.770089	0.049429	0.087933	-0.036772
+1.036433	0.026334	-0.026334	9.803606	0.049962	0.089931	-0.037305
+1.037420	0.002394	-0.004788	9.861063	0.049562	0.091130	-0.035306
+1.038418	0.011970	0.031123	9.839517	0.047430	0.089265	-0.031842
+1.039420	0.007182	0.002394	9.779666	0.047297	0.090064	-0.032642
+1.040489	0.000000	-0.002394	9.762907	0.048629	0.088732	-0.035573
+1.041490	-0.038305	0.028729	9.789242	0.047963	0.087533	-0.038504
+1.042493	-0.019152	0.009576	9.815576	0.048763	0.089265	-0.036639
+1.043448	-0.011970	-0.004788	9.758119	0.049429	0.088066	-0.032109
+1.044459	0.031123	-0.007182	9.750937	0.051161	0.087400	-0.035040
+1.045431	0.026334	-0.055063	9.750937	0.049162	0.088332	-0.036505
+1.046492	0.016758	-0.028729	9.758119	0.046364	0.089398	-0.038371
+1.047489	0.007182	-0.004788	9.837123	0.044899	0.090198	-0.038371
+1.048468	0.011970	-0.083792	9.786848	0.047164	0.090064	-0.038504
+1.049433	-0.019152	-0.033517	9.832334	0.048096	0.089665	-0.037838
+1.050485	0.040699	-0.031123	9.849093	0.047830	0.087933	-0.037038
+1.051439	0.009576	0.014364	9.832334	0.048230	0.087799	-0.036772
+1.052429	-0.035911	0.023940	9.796424	0.049828	0.085934	-0.037438
+1.053421	0.047881	-0.035911	9.794030	0.048496	0.087133	-0.029977
+1.054399	0.071821	-0.031123	9.858669	0.047963	0.087666	-0.034507
+1.055483	0.040699	-0.004788	9.899368	0.049962	0.086067	-0.037838
+1.056485	0.081397	-0.040699	9.885003	0.050628	0.085801	-0.035972
+1.057492	0.040699	-0.011970	9.853881	0.048230	0.089132	-0.036772
+1.058493	0.045487	-0.052669	9.856275	0.047164	0.089265	-0.034374
+1.059489	0.009576	-0.045487	9.806000	0.049029	0.087666	-0.037038
+1.060490	-0.004788	-0.035911	9.796424	0.051028	0.088332	-0.035040
+1.061431	-0.028729	-0.019152	9.738967	0.050095	0.089531	-0.035839
+1.062395	0.007182	-0.014364	9.798818	0.046364	0.090198	-0.036772
+1.063425	0.052669	0.000000	9.856275	0.045032	0.090198	-0.037172
+1.064460	0.071821	-0.026334	9.782060	0.046897	0.088066	-0.035972
+1.065439	0.055063	-0.045487	9.774877	0.048629	0.085934	-0.036639
+1.066432	0.000000	-0.035911	9.815576	0.048629	0.087533	-0.038237
+1.067427	-0.021546	0.009576	9.810788	0.049429	0.088732	-0.037172
+1.068412	0.004788	0.014364	9.858669	0.047963	0.090597	-0.035706
+1.069491	0.083792	-0.033517	9.894580	0.047031	0.089931	-0.033574
+1.070491	0.062245	-0.047881	9.801212	0.047697	0.088865	-0.038904
+1.071489	0.011970	0.014364	9.801212	0.047830	0.086734	-0.036505
+1.072461	-0.007182	0.059851	9.767695	0.046098	0.086867	-0.034240
+1.073445	-0.023940	0.009576	9.789242	0.048496	0.086467	-0.031975
+1.074433	-0.067033	-0.059851	9.846699	0.049562	0.085401	-0.033974
+1.075426	0.011970	-0.033517	9.810788	0.049162	0.083802	-0.037172
+1.076490	0.004788	-0.019152	9.772483	0.048629	0.086867	-0.038371
+1.077492	-0.033517	0.045487	9.789242	0.048096	0.091530	-0.039170
+1.078489	0.000000	0.009576	9.789242	0.047697	0.090864	-0.038904
+1.079490	0.057457	0.011970	9.729391	0.047830	0.088732	-0.038371
+1.080488	0.021546	0.016758	9.762907	0.047697	0.088599	-0.035440
+1.081496	0.016758	-0.004788	9.765301	0.048230	0.088199	-0.034773
+1.082446	-0.014364	-0.026334	9.782060	0.050628	0.086334	-0.036505
+1.083447	0.031123	-0.009576	9.717420	0.051427	0.087533	-0.036905
+1.084489	0.079003	-0.004788	9.743755	0.051427	0.087000	-0.034907
+1.085410	0.050275	0.040699	9.734179	0.048496	0.091530	-0.034773
+1.086491	0.028729	0.000000	9.731785	0.046364	0.092995	-0.035040
+1.087489	-0.047881	-0.026334	9.796424	0.047297	0.088066	-0.034107
+1.088489	-0.040699	0.007182	9.851487	0.047031	0.084602	-0.034640
+1.089451	-0.007182	0.023940	9.834729	0.046897	0.085534	-0.036505
+1.090491	-0.031123	-0.023940	9.803606	0.047164	0.087400	-0.035972
+1.091446	0.033517	-0.011970	9.801212	0.049828	0.088466	-0.037305
+1.092482	0.055063	-0.071821	9.770089	0.050761	0.088332	-0.037571
+1.093487	0.033517	-0.031123	9.841911	0.050228	0.087666	-0.036372
+1.094426	0.009576	-0.043093	9.791636	0.050095	0.089665	-0.033708
+1.095489	0.047881	-0.035911	9.760513	0.047031	0.088332	-0.033441
+1.096489	0.009576	-0.038305	9.753331	0.046098	0.088066	-0.037172
+1.097489	-0.052669	-0.016758	9.817970	0.046364	0.087933	-0.036905
+1.098490	0.016758	0.028729	9.815576	0.045032	0.087933	-0.037838
+1.099444	0.009576	0.047881	9.784454	0.048496	0.088865	-0.036772
+1.100445	0.026334	-0.004788	9.755725	0.048629	0.086867	-0.035839
+1.101425	0.038305	0.009576	9.858669	0.049562	0.087000	-0.037172
+1.102492	0.009576	-0.004788	9.808394	0.049162	0.083802	-0.037305
+1.103486	-0.043093	-0.079003	9.784454	0.047697	0.084735	-0.031576
+1.104490	-0.016758	-0.055063	9.803606	0.044766	0.086201	-0.034907
+1.105490	-0.011970	-0.023940	9.834729	0.044632	0.085801	-0.040502
+1.106491	-0.067033	-0.016758	9.882609	0.047564	0.088332	-0.037172
+1.107443	0.050275	-0.002394	9.858669	0.049162	0.090730	-0.038637
+1.108490	0.071821	-0.026334	9.815576	0.047830	0.090064	-0.036372
+1.109448	0.026334	-0.026334	9.738967	0.047430	0.089531	-0.031842
+1.110430	0.028729	0.000000	9.796424	0.049296	0.089265	-0.034640
+1.111489	0.035911	-0.002394	9.880215	0.049562	0.088732	-0.039436
+1.112422	0.026334	-0.026334	9.858669	0.047697	0.089665	-0.038371
+1.113418	0.043093	0.019152	9.865851	0.044233	0.086867	-0.037438
+1.114392	0.016758	-0.040699	9.779666	0.045565	0.088466	-0.036639
+1.115402	-0.040699	0.031123	9.715026	0.049296	0.089665	-0.034507
+1.116402	-0.028729	0.011970	9.827546	0.050361	0.089798	-0.036372
+1.117397	0.014364	0.014364	9.839517	0.047963	0.085934	-0.037172
+1.118417	-0.047881	0.014364	9.741361	0.047830	0.086067	-0.035306
+1.119424	-0.055063	-0.021546	9.765301	0.048230	0.086734	-0.037038
+1.120416	-0.031123	-0.079003	9.827546	0.046764	0.090864	-0.036239
+1.121420	0.004788	-0.009576	9.789242	0.048230	0.089531	-0.035839
+1.122424	-0.014364	-0.021546	9.782060	0.048496	0.087933	-0.039303
+1.123426	-0.028729	-0.052669	9.789242	0.046098	0.086600	-0.038770
+1.124426	-0.038305	-0.035911	9.770089	0.045299	0.086201	-0.038104
+1.125488	0.062245	-0.004788	9.724603	0.044632	0.087933	-0.037704
+1.126490	0.021546	0.000000	9.765301	0.045832	0.089531	-0.033974
+1.127490	0.040699	-0.050275	9.803606	0.048230	0.090597	-0.035440
+1.128489	0.023940	-0.033517	9.748543	0.047830	0.087266	-0.040103
+1.129489	0.014364	-0.047881	9.820364	0.048230	0.085668	-0.038104
+1.130489	0.031123	-0.026334	9.796424	0.049029	0.087799	-0.032775
+1.131446	0.009576	0.014364	9.779666	0.048763	0.087000	-0.033441
+1.132485	0.040699	-0.033517	9.719814	0.048230	0.087133	-0.034507
+1.133488	0.035911	0.007182	9.829940	0.047031	0.087933	-0.035040
+1.134411	0.071821	-0.016758	9.762907	0.047164	0.087400	-0.037971
+1.135424	0.009576	-0.040699	9.794030	0.048763	0.087133	-0.038371
+1.136488	0.033517	-0.059851	9.806000	0.048230	0.085801	-0.037172
+1.137489	0.033517	-0.062245	9.846699	0.047963	0.087400	-0.032109
+1.138490	0.016758	-0.040699	9.817970	0.050095	0.089265	-0.033308
+1.139423	-0.002394	0.007182	9.762907	0.047697	0.088466	-0.034374
+1.140469	-0.009576	0.050275	9.700662	0.045032	0.086067	-0.039570
+1.141488	-0.040699	0.045487	9.748543	0.047830	0.087933	-0.040636
+1.142492	-0.023940	0.007182	9.746149	0.051294	0.086467	-0.041168
+1.143492	0.033517	0.021546	9.770089	0.050628	0.086867	-0.036772
+1.144488	0.043093	0.052669	9.760513	0.048496	0.087533	-0.035839
+1.145493	0.059851	0.016758	9.789242	0.046498	0.091263	-0.035440
+1.146492	0.059851	0.000000	9.794030	0.044899	0.089798	-0.037305
+1.147488	-0.002394	0.040699	9.863457	0.045299	0.087933	-0.037438
+1.148423	-0.055063	0.021546	9.841911	0.045299	0.087400	-0.036372
+1.149453	0.043093	-0.031123	9.762907	0.044632	0.088732	-0.037172
+1.150489	0.047881	0.011970	9.767695	0.047031	0.087133	-0.034907
+1.151489	0.007182	-0.045487	9.794030	0.047031	0.087799	-0.036239
+1.152405	-0.031123	-0.071821	9.858669	0.047963	0.090064	-0.037971
+1.153493	-0.019152	-0.023940	9.782060	0.048096	0.089665	-0.036905
+1.154489	-0.057457	0.009576	9.719814	0.046897	0.087400	-0.033574
+1.155495	-0.021546	-0.011970	9.813182	0.045432	0.086734	-0.033708
+1.156491	0.021546	-0.007182	9.782060	0.045832	0.086201	-0.036639
+1.157414	0.011970	0.014364	9.746149	0.046897	0.085401	-0.039436
+1.158447	0.033517	0.033517	9.779666	0.046098	0.087533	-0.037438
+1.159488	0.011970	0.026334	9.794030	0.046364	0.090730	-0.036772
+1.160428	0.023940	0.007182	9.782060	0.047963	0.090331	-0.037305
+1.161489	0.002394	-0.026334	9.741361	0.048763	0.088732	-0.036372
+1.162445	0.011970	0.009576	9.782060	0.046098	0.087933	-0.033974
+1.163414	0.026334	-0.062245	9.849093	0.046231	0.088865	-0.033041
+1.164481	0.033517	-0.026334	9.817970	0.046098	0.088332	-0.031176
+1.165363	0.016758	-0.004788	9.779666	0.044899	0.085268	-0.035306
+1.166391	-0.014364	-0.009576	9.813182	0.045832	0.084069	-0.035972
+1.167389	-0.026334	0.038305	9.772483	0.048896	0.084335	-0.037438
+1.168394	-0.014364	-0.004788	9.834729	0.049962	0.087933	-0.036239
+1.169447	0.026334	0.007182	9.810788	0.049695	0.089132	-0.035440
+1.170492	-0.002394	0.021546	9.772483	0.047697	0.086867	-0.038504
+1.171492	-0.093368	-0.019152	9.796424	0.044366	0.087133	-0.040769
+1.172488	-0.014364	0.000000	9.762907	0.044233	0.089265	-0.040236
+1.173488	0.014364	0.007182	9.777271	0.048096	0.087933	-0.040769
+1.174431	0.016758	-0.009576	9.779666	0.049828	0.087533	-0.039436
+1.175487	0.009576	0.009576	9.822758	0.045299	0.086734	-0.038371
+1.176443	0.055063	0.011970	9.844305	0.045432	0.088332	-0.038237
+1.177481	0.031123	-0.019152	9.853881	0.047430	0.090997	-0.036106
+1.178491	0.019152	-0.004788	9.846699	0.046897	0.089398	-0.037838
+1.179489	0.031123	-0.004788	9.851487	0.047031	0.086734	-0.035306
+1.180488	0.021546	0.002394	9.832334	0.047697	0.084602	-0.035173
+1.181453	0.021546	-0.026334	9.923308	0.049296	0.084735	-0.037038
+1.182468	0.009576	-0.059851	9.873033	0.047430	0.087799	-0.039037
+1.183488	-0.019152	-0.016758	9.810788	0.046897	0.088332	-0.036639
+1.184427	-0.035911	-0.011970	9.772483	0.047297	0.086201	-0.035839
+1.185403	-0.014364	0.028729	9.738967	0.048896	0.083536	-0.037571
+1.186485	-0.019152	0.028729	9.729391	0.049695	0.083403	-0.037172
+1.187422	-0.043093	-0.016758	9.806000	0.047697	0.087133	-0.037438
+1.188488	-0.016758	-0.031123	9.784454	0.045698	0.087666	-0.035173
+1.189492	-0.031123	0.028729	9.786848	0.045299	0.088732	-0.036505
+1.190491	-0.033517	-0.023940	9.767695	0.047031	0.087400	-0.034907
+1.191488	0.026334	-0.023940	9.772483	0.045698	0.088199	-0.037704
+1.192487	0.035911	-0.052669	9.774877	0.046231	0.090464	-0.039436
+1.193452	0.035911	-0.028729	9.743755	0.046098	0.091397	-0.039037
+1.194417	0.059851	-0.009576	9.779666	0.046098	0.088199	-0.037172
+1.195481	0.052669	-0.007182	9.832334	0.045432	0.084602	-0.032908
+1.196491	-0.019152	0.007182	9.832334	0.045165	0.085534	-0.036239
+1.197490	-0.004788	-0.033517	9.810788	0.048896	0.088332	-0.036772
+1.198491	-0.014364	-0.038305	9.750937	0.049429	0.086201	-0.036239
+1.199448	-0.004788	-0.031123	9.758119	0.045832	0.085668	-0.034907
+1.200407	0.021546	-0.011970	9.832334	0.043167	0.085668	-0.036905
+1.201398	0.040699	-0.016758	9.746149	0.045165	0.088998	-0.036905
+1.202413	0.040699	-0.055063	9.758119	0.047830	0.088466	-0.036106
+1.203416	0.011970	0.000000	9.846699	0.047697	0.085668	-0.035573
+1.204413	-0.021546	-0.004788	9.844305	0.046897	0.085401	-0.036772
+1.205418	-0.059851	0.002394	9.832334	0.048363	0.088199	-0.034507
+1.206424	0.035911	-0.016758	9.817970	0.048363	0.090464	-0.033841
+1.207414	0.004788	0.011970	9.844305	0.046498	0.088199	-0.035040
+1.208403	0.031123	0.040699	9.762907	0.045965	0.086734	-0.037971
+1.209427	0.050275	0.047881	9.798818	0.047963	0.085668	-0.036505
+1.210420	0.081397	0.009576	9.791636	0.048763	0.089665	-0.036639
+1.211421	0.081397	0.016758	9.784454	0.047830	0.090198	-0.036772
+1.212393	0.031123	0.002394	9.844305	0.047830	0.085934	-0.033841
+1.213423	0.004788	0.002394	9.803606	0.046498	0.084335	-0.034773
+1.214421	0.021546	0.031123	9.791636	0.045165	0.084868	-0.034374
+1.215417	-0.019152	-0.004788	9.791636	0.045165	0.087666	-0.034107
+1.216417	0.014364	-0.021546	9.863457	0.047297	0.091130	-0.036372
+1.217423	-0.014364	-0.035911	9.820364	0.047297	0.090198	-0.038770
+1.218414	-0.011970	-0.014364	9.755725	0.044766	0.087666	-0.036372
+1.219487	0.000000	0.033517	9.765301	0.047164	0.085668	-0.037838
+1.220488	-0.031123	0.035911	9.715026	0.048363	0.087400	-0.036905
+1.221488	-0.023940	0.007182	9.734179	0.046764	0.088998	-0.037704
+1.222491	-0.007182	0.014364	9.846699	0.046897	0.091397	-0.037305
+1.223485	0.052669	0.031123	9.810788	0.046098	0.093795	-0.037838
+1.224439	0.019152	-0.007182	9.801212	0.046364	0.088466	-0.040502
+1.225424	0.047881	-0.038305	9.803606	0.047564	0.084602	-0.039836
+1.226446	0.000000	-0.019152	9.810788	0.049429	0.087666	-0.036372
+1.227433	-0.014364	-0.016758	9.789242	0.047830	0.089265	-0.034773
+1.228500	-0.004788	0.067033	9.789242	0.043966	0.090730	-0.036772
+1.229489	-0.016758	0.050275	9.837123	0.045032	0.090064	-0.038371
+1.230491	-0.031123	-0.079003	9.825152	0.047430	0.090464	-0.039570
+1.231489	-0.021546	-0.026334	9.789242	0.048763	0.090597	-0.037971
+1.232487	0.000000	0.021546	9.798818	0.048230	0.087933	-0.037571
+1.233487	0.016758	0.000000	9.798818	0.044499	0.087266	-0.040369
+1.234406	0.050275	-0.002394	9.822758	0.044100	0.087400	-0.038504
+1.235423	0.071821	0.000000	9.829940	0.047963	0.087666	-0.038371
+1.236476	0.019152	-0.011970	9.784454	0.048096	0.088865	-0.039170
+1.237487	-0.023940	-0.031123	9.853881	0.046098	0.086600	-0.039436
+1.238493	0.043093	-0.062245	9.841911	0.047430	0.083802	-0.036106
+1.239405	0.047881	-0.040699	9.803606	0.047830	0.084202	-0.035972
+1.240487	0.050275	-0.011970	9.822758	0.048629	0.086867	-0.037838
+1.241488	-0.023940	0.019152	9.858669	0.049296	0.089265	-0.036239
+1.242488	-0.040699	0.023940	9.753331	0.049296	0.088466	-0.033708
+1.243489	0.011970	0.016758	9.743755	0.048896	0.088332	-0.035573
+1.244400	0.043093	0.035911	9.813182	0.046364	0.088732	-0.037305
+1.245482	0.026334	-0.050275	9.810788	0.044766	0.087000	-0.037571
+1.246431	-0.059851	0.000000	9.829940	0.045432	0.087133	-0.039836
+1.247422	0.021546	0.067033	9.856275	0.045165	0.088865	-0.040636
+1.248423	0.040699	0.040699	9.832334	0.045165	0.091130	-0.041435
+1.249487	0.031123	-0.007182	9.827546	0.045965	0.093129	-0.037172
+1.250424	0.043093	-0.016758	9.808394	0.047430	0.090997	-0.036372
+1.251487	0.004788	-0.040699	9.817970	0.047430	0.086334	-0.035440
+1.252445	0.028729	0.016758	9.822758	0.046498	0.085801	-0.037305
+1.253489	-0.031123	0.031123	9.834729	0.042634	0.088066	-0.039037
+1.254448	-0.009576	0.021546	9.829940	0.042634	0.087266	-0.040236
+1.255491	-0.031123	0.040699	9.856275	0.047031	0.086600	-0.037704
+1.256444	-0.016758	0.023940	9.717420	0.049962	0.086600	-0.038904
+1.257447	0.002394	0.007182	9.784454	0.046364	0.086600	-0.040103
+1.258432	-0.004788	-0.004788	9.810788	0.047164	0.088599	-0.040103
+1.259443	0.007182	-0.071821	9.839517	0.048496	0.089531	-0.034907
+1.260434	0.052669	0.000000	9.877821	0.047164	0.091130	-0.034107
+1.261485	0.021546	-0.019152	9.882609	0.047164	0.091397	-0.036905
+1.262418	0.045487	0.021546	9.841911	0.046631	0.089931	-0.034507
+1.263387	0.023940	-0.004788	9.791636	0.043300	0.086067	-0.034773
+1.264491	0.009576	-0.002394	9.779666	0.046098	0.085268	-0.037971
+1.265430	0.016758	-0.038305	9.803606	0.049695	0.086334	-0.040236
+1.266435	0.011970	-0.052669	9.815576	0.047297	0.090464	-0.037971
+1.267444	-0.011970	-0.052669	9.784454	0.046364	0.090597	-0.036905
+1.268394	-0.004788	-0.011970	9.837123	0.047564	0.089265	-0.035972
+1.269396	0.019152	0.040699	9.856275	0.046498	0.089931	-0.036905
+1.270398	0.026334	-0.002394	9.829940	0.047830	0.092196	-0.039303
+1.271393	-0.019152	-0.038305	9.803606	0.049162	0.090064	-0.037571
+1.272391	-0.064639	-0.019152	9.782060	0.047963	0.088466	-0.035306
+1.273394	0.004788	0.047881	9.846699	0.047697	0.088466	-0.037438
+1.274343	0.021546	0.019152	9.865851	0.046364	0.089398	-0.036239
+1.275385	0.021546	-0.007182	9.853881	0.047031	0.087133	-0.036639
+1.276379	0.038305	-0.052669	9.755725	0.045565	0.086600	-0.036505
+1.277338	0.043093	-0.045487	9.789242	0.046764	0.086067	-0.036639
+1.278363	0.071821	-0.023940	9.746149	0.047830	0.084469	-0.034507
+1.279341	0.050275	-0.088580	9.770089	0.045432	0.087933	-0.037438
+1.280342	-0.016758	-0.004788	9.870639	0.044899	0.088732	-0.039303
+1.281344	-0.035911	-0.062245	9.810788	0.047430	0.087000	-0.034374
+1.282342	-0.023940	-0.038305	9.774877	0.047830	0.088998	-0.032775
+1.283342	-0.016758	-0.023940	9.772483	0.047963	0.089798	-0.035173
+1.284341	0.014364	-0.014364	9.794030	0.048230	0.088199	-0.037571
+1.285343	-0.016758	-0.019152	9.841911	0.048629	0.088466	-0.034240
+1.286341	0.002394	-0.021546	9.806000	0.047297	0.089132	-0.035440
+1.287345	0.055063	-0.028729	9.822758	0.046231	0.089931	-0.036505
+1.288344	-0.026334	0.007182	9.815576	0.049562	0.088732	-0.036372
+1.289345	0.009576	0.014364	9.803606	0.050361	0.086467	-0.038770
+1.290340	0.031123	0.014364	9.777271	0.047430	0.085401	-0.037038
+1.291395	-0.016758	0.038305	9.839517	0.045432	0.085534	-0.039037
+1.292443	0.026334	0.019152	9.786848	0.046231	0.087266	-0.040902
+1.293416	0.014364	-0.002394	9.770089	0.047031	0.087799	-0.035573
+1.294410	0.011970	-0.067033	9.825152	0.048763	0.088865	-0.032242
+1.295434	0.052669	-0.055063	9.784454	0.045698	0.088599	-0.032908
+1.296432	0.014364	0.023940	9.820364	0.043966	0.088865	-0.036106
+1.297433	0.019152	0.021546	9.820364	0.046364	0.088865	-0.037971
+1.298434	0.009576	0.007182	9.892186	0.045965	0.088466	-0.034374
+1.299427	0.038305	0.014364	9.863457	0.046364	0.089665	-0.036905
+1.300434	0.016758	-0.009576	9.767695	0.047963	0.089798	-0.038637
+1.301365	0.021546	0.016758	9.772483	0.049029	0.089265	-0.037704
+1.302391	0.011970	0.000000	9.808394	0.047564	0.090198	-0.035573
+1.303432	-0.019152	-0.014364	9.758119	0.047830	0.088466	-0.035839
+1.304361	0.007182	-0.067033	9.839517	0.046364	0.086067	-0.035306
+1.305436	0.011970	-0.009576	9.794030	0.046098	0.088066	-0.035173
+1.306391	0.055063	-0.059851	9.786848	0.047164	0.090464	-0.038504
+1.307409	-0.023940	-0.009576	9.784454	0.049296	0.090064	-0.037571
+1.308366	-0.021546	-0.004788	9.808394	0.047297	0.088732	-0.038637
+1.309433	0.040699	-0.047881	9.817970	0.046364	0.087133	-0.036639
+1.310432	0.004788	-0.033517	9.770089	0.043567	0.086334	-0.035573
+1.311433	-0.023940	-0.016758	9.750937	0.045832	0.085534	-0.037438
+1.312374	-0.007182	-0.040699	9.722208	0.047164	0.088599	-0.037038
+1.313370	-0.011970	-0.052669	9.700662	0.046498	0.085934	-0.037305
+1.314387	0.028729	-0.069427	9.810788	0.046098	0.087133	-0.038237
+1.315399	0.023940	-0.040699	9.817970	0.048096	0.088332	-0.038504
+1.316431	0.019152	-0.035911	9.813182	0.046897	0.090064	-0.037838
+1.317434	-0.021546	-0.107732	9.794030	0.046231	0.090064	-0.037438
+1.318388	-0.059851	-0.074215	9.798818	0.047297	0.089665	-0.035706
+1.319432	0.043093	-0.002394	9.772483	0.048496	0.087400	-0.037305
+1.320350	0.050275	0.045487	9.856275	0.047564	0.086334	-0.037971
+1.321433	0.043093	-0.028729	9.774877	0.045698	0.085401	-0.037704
+1.322400	0.007182	-0.014364	9.767695	0.043567	0.087533	-0.033574
+1.323394	-0.031123	0.007182	9.844305	0.044499	0.088865	-0.033308
+1.324433	0.009576	0.014364	9.817970	0.045032	0.087400	-0.038770
+1.325363	0.000000	-0.026334	9.806000	0.045432	0.086867	-0.037838
+1.326364	0.007182	-0.045487	9.817970	0.045565	0.087266	-0.037038
+1.327434	-0.014364	-0.035911	9.758119	0.045965	0.089265	-0.035040
+1.328433	0.016758	0.004788	9.789242	0.046498	0.088732	-0.034907
+1.329434	0.038305	0.055063	9.796424	0.047963	0.086867	-0.036772
+1.330436	-0.007182	0.033517	9.839517	0.047430	0.085002	-0.036239
+1.331436	-0.009576	-0.007182	9.839517	0.046764	0.086201	-0.032908
+1.332435	0.002394	-0.062245	9.782060	0.046364	0.087133	-0.034240
+1.333363	-0.028729	-0.028729	9.753331	0.047564	0.088199	-0.037704
+1.334364	0.021546	0.016758	9.789242	0.048896	0.088332	-0.039303
+1.335376	-0.047881	0.002394	9.782060	0.048496	0.086867	-0.038504
+1.336432	-0.031123	-0.038305	9.803606	0.045965	0.088332	-0.034907
+1.337414	0.000000	-0.038305	9.829940	0.045299	0.088466	-0.033441
+1.338435	-0.028729	-0.031123	9.868245	0.047164	0.090464	-0.033974
+1.339432	0.002394	-0.043093	9.844305	0.047830	0.090464	-0.034640
+1.340392	0.016758	-0.011970	9.834729	0.047164	0.090064	-0.035839
+1.341433	-0.011970	-0.031123	9.841911	0.049162	0.087266	-0.037838
+1.342448	0.047881	-0.004788	9.794030	0.047830	0.087666	-0.037971
+1.343385	0.014364	-0.002394	9.765301	0.047564	0.089132	-0.038104
+1.344435	-0.009576	-0.002394	9.750937	0.046231	0.090064	-0.035573
+1.345436	-0.045487	0.000000	9.703056	0.046498	0.090331	-0.038371
+1.346437	-0.040699	0.016758	9.772483	0.046098	0.086867	-0.037838
+1.347416	0.011970	0.007182	9.806000	0.045565	0.087266	-0.037438
+1.348436	0.016758	-0.031123	9.755725	0.046764	0.090464	-0.036106
+1.349434	0.040699	0.021546	9.815576	0.045032	0.090331	-0.032775
+1.350405	0.009576	0.023940	9.784454	0.044899	0.088466	-0.037571
+1.351434	0.035911	-0.047881	9.865851	0.044766	0.087933	-0.040902
+1.352428	0.011970	-0.052669	9.827546	0.045965	0.087666	-0.036106
+1.353392	0.016758	-0.011970	9.822758	0.046764	0.088466	-0.035040
+1.354433	-0.023940	0.002394	9.870639	0.045299	0.085668	-0.036106
+1.355419	0.000000	0.019152	9.853881	0.045432	0.085668	-0.035706
+1.356434	0.007182	-0.016758	9.873033	0.047297	0.086067	-0.034640
+1.357428	0.031123	-0.021546	9.829940	0.047564	0.086334	-0.034640
+1.358403	0.023940	0.009576	9.798818	0.047031	0.088865	-0.035706
+1.359388	0.016758	0.002394	9.827546	0.047164	0.089132	-0.035706
+1.360427	0.004788	-0.021546	9.806000	0.047697	0.087933	-0.037971
+1.361432	-0.052669	0.035911	9.753331	0.046764	0.088199	-0.040369
+1.362399	-0.045487	0.007182	9.832334	0.045299	0.088199	-0.037038
+1.363374	-0.014364	-0.007182	9.758119	0.044632	0.088732	-0.034240
+1.364428	0.028729	0.026334	9.784454	0.046631	0.084735	-0.036372
+1.365433	0.033517	-0.002394	9.827546	0.047963	0.083936	-0.036772
+1.366435	-0.035911	-0.009576	9.815576	0.046631	0.086600	-0.034507
+1.367431	-0.007182	0.007182	9.873033	0.046098	0.089398	-0.036905
+1.368432	0.028729	-0.028729	9.755725	0.048230	0.089398	-0.039969
+1.369433	0.033517	-0.071821	9.762907	0.045698	0.089931	-0.039836
+1.370433	0.052669	-0.052669	9.796424	0.043700	0.089531	-0.036239
+1.371431	0.026334	0.000000	9.817970	0.046498	0.088066	-0.033708
+1.372432	-0.021546	0.019152	9.863457	0.049296	0.090198	-0.035440
+1.373386	-0.014364	-0.002394	9.882609	0.048763	0.088599	-0.037838
+1.374426	0.043093	0.023940	9.892186	0.046897	0.087533	-0.035972
+1.375416	0.023940	0.004788	9.853881	0.045299	0.087666	-0.033574
+1.376394	0.026334	-0.040699	9.779666	0.045165	0.089798	-0.034907
+1.377340	0.047881	-0.031123	9.758119	0.045832	0.088998	-0.038237
+1.378364	0.014364	-0.057457	9.743755	0.045832	0.087000	-0.038504
+1.379433	0.016758	-0.028729	9.789242	0.044233	0.084069	-0.037704
+1.380353	0.011970	-0.021546	9.801212	0.044499	0.082870	-0.036239
+1.381345	0.043093	0.002394	9.712632	0.047963	0.086067	-0.034107
+1.382392	0.033517	0.026334	9.743755	0.049029	0.088865	-0.036772
+1.383423	0.050275	0.002394	9.817970	0.046098	0.088599	-0.036239
+1.384409	0.045487	-0.011970	9.813182	0.046098	0.087000	-0.033708
+1.385403	-0.009576	0.028729	9.815576	0.048096	0.084868	-0.035173
+1.386491	-0.016758	-0.007182	9.829940	0.048496	0.088865	-0.037838
+1.387400	0.035911	0.047881	9.841911	0.047564	0.091796	-0.036239
+1.388393	0.038305	0.062245	9.815576	0.045432	0.091530	-0.033841
+1.389391	0.043093	0.045487	9.906550	0.045698	0.088998	-0.032642
+1.390395	0.023940	-0.007182	9.858669	0.047430	0.088865	-0.033974
+1.391390	0.009576	0.004788	9.734179	0.046764	0.085934	-0.036905
+1.392390	-0.004788	0.050275	9.772483	0.047297	0.085934	-0.037305
+1.393392	-0.014364	-0.007182	9.750937	0.048363	0.087133	-0.034240
+1.394411	-0.033517	0.000000	9.748543	0.046631	0.090331	-0.033441
+1.395485	-0.028729	-0.040699	9.820364	0.047697	0.087933	-0.034107
+1.396484	-0.040699	-0.040699	9.810788	0.046631	0.087000	-0.036639
+1.397486	0.033517	-0.021546	9.791636	0.047697	0.086867	-0.038104
+1.398488	0.045487	-0.021546	9.734179	0.048230	0.085268	-0.038504
+1.399426	0.007182	-0.043093	9.760513	0.046764	0.085002	-0.036372
+1.400388	-0.028729	0.021546	9.779666	0.045165	0.088332	-0.034907
+1.401396	-0.028729	0.016758	9.796424	0.044499	0.088732	-0.035440
+1.402389	0.004788	-0.019152	9.820364	0.045832	0.089265	-0.039836
+1.403435	0.007182	-0.052669	9.868245	0.045965	0.089531	-0.040902
+1.404394	0.057457	-0.028729	9.899368	0.046231	0.088466	-0.038371
+1.405426	0.016758	-0.021546	9.832334	0.048496	0.089132	-0.037438
+1.406442	-0.055063	-0.028729	9.798818	0.047564	0.091397	-0.038637
+1.407435	0.035911	-0.002394	9.755725	0.046364	0.091663	-0.038237
+1.408438	0.007182	0.026334	9.770089	0.047697	0.089665	-0.035972
+1.409439	0.026334	0.033517	9.806000	0.048363	0.089398	-0.034107
+1.410370	0.026334	-0.009576	9.863457	0.045299	0.089398	-0.034773
+1.411436	-0.019152	-0.033517	9.880215	0.044100	0.087799	-0.037038
+1.412435	-0.007182	0.023940	9.861063	0.045965	0.085934	-0.037971
+1.413392	-0.002394	0.026334	9.832334	0.047164	0.087533	-0.036772
+1.414348	-0.002394	-0.019152	9.746149	0.045832	0.088865	-0.034907
+1.415403	0.007182	-0.028729	9.762907	0.045698	0.088865	-0.034240
+1.416436	-0.019152	-0.059851	9.832334	0.048496	0.087266	-0.034507
+1.417418	-0.038305	-0.038305	9.794030	0.050228	0.088199	-0.035573
+1.418355	-0.019152	-0.033517	9.736573	0.047697	0.089265	-0.038104
+1.419346	0.050275	-0.045487	9.784454	0.048363	0.088466	-0.036372
+1.420346	0.033517	-0.016758	9.815576	0.046764	0.088599	-0.036372
+1.421437	0.019152	-0.016758	9.825152	0.046231	0.088865	-0.035306
+1.422437	0.047881	-0.043093	9.784454	0.049562	0.088865	-0.037971
+1.423438	-0.023940	0.040699	9.782060	0.051294	0.088732	-0.035306
+1.424440	0.028729	0.052669	9.782060	0.049429	0.088466	-0.035573
+1.425374	-0.026334	0.011970	9.774877	0.045032	0.087666	-0.036372
+1.426377	-0.033517	-0.002394	9.722208	0.044632	0.088466	-0.035839
+1.427405	-0.016758	-0.002394	9.817970	0.045032	0.087266	-0.039303
+1.428437	-0.011970	-0.009576	9.810788	0.044366	0.086201	-0.034773
+1.429435	-0.009576	0.040699	9.832334	0.045965	0.087933	-0.033441
+1.430439	-0.009576	0.040699	9.832334	0.045832	0.087000	-0.036239
+1.431434	0.038305	0.004788	9.834729	0.048230	0.087533	-0.036772
+1.432436	0.047881	0.014364	9.806000	0.048763	0.088599	-0.037838
+1.433438	0.021546	0.016758	9.798818	0.047297	0.088865	-0.035706
+1.434369	0.011970	0.086186	9.870639	0.047031	0.087133	-0.033574
+1.435403	-0.028729	0.043093	9.861063	0.045432	0.086334	-0.037038
+1.436437	-0.004788	0.007182	9.849093	0.043833	0.089265	-0.034773
+1.437438	-0.023940	0.028729	9.808394	0.047564	0.088998	-0.034507
+1.438439	0.026334	-0.019152	9.829940	0.046897	0.089531	-0.033974
+1.439437	0.038305	-0.040699	9.810788	0.045965	0.087400	-0.039037
+1.440435	0.009576	-0.002394	9.837123	0.045698	0.088998	-0.040502
+1.441438	-0.026334	-0.009576	9.777271	0.048096	0.091796	-0.039836
+1.442438	-0.009576	-0.028729	9.810788	0.046231	0.089931	-0.034907
+1.443435	-0.009576	0.064639	9.803606	0.045299	0.086867	-0.034907
+1.444426	-0.043093	0.000000	9.803606	0.045032	0.085401	-0.036905
+1.445401	0.000000	0.016758	9.863457	0.046631	0.088066	-0.034640
+1.446437	0.033517	-0.021546	9.887397	0.049162	0.087799	-0.035306
+1.447430	0.052669	-0.023940	9.858669	0.049562	0.088466	-0.037571
+1.448431	0.047881	-0.028729	9.858669	0.047564	0.087000	-0.036372
+1.449364	0.004788	0.028729	9.827546	0.047697	0.087533	-0.035306
+1.450472	0.038305	-0.019152	9.834729	0.047031	0.086334	-0.035306
+1.451436	0.011970	-0.031123	9.782060	0.046897	0.087266	-0.036106
+1.452435	-0.047881	-0.009576	9.806000	0.046897	0.088332	-0.032642
+1.453436	-0.019152	0.043093	9.801212	0.046098	0.086867	-0.034107
+1.454370	-0.011970	-0.016758	9.772483	0.046364	0.086067	-0.036106
+1.455400	-0.055063	0.023940	9.806000	0.046098	0.086867	-0.036639
+1.456434	-0.023940	0.007182	9.794030	0.048496	0.088199	-0.037172
+1.457438	0.004788	0.009576	9.806000	0.047297	0.089398	-0.037438
+1.458436	-0.019152	0.023940	9.808394	0.048096	0.088732	-0.035972
+1.459432	0.002394	-0.011970	9.853881	0.048496	0.088199	-0.037571
+1.460436	0.035911	0.016758	9.762907	0.045832	0.088466	-0.040502
+1.461435	0.026334	0.011970	9.734179	0.047830	0.089265	-0.037172
+1.462437	0.028729	-0.014364	9.810788	0.048496	0.088466	-0.036639
+1.463376	0.050275	0.007182	9.861063	0.049162	0.085934	-0.037438
+1.464372	0.095762	0.035911	9.760513	0.048363	0.086600	-0.035440
+1.465368	0.045487	0.009576	9.765301	0.050361	0.087533	-0.034773
+1.466386	0.000000	-0.031123	9.789242	0.050495	0.085934	-0.036505
+1.467441	0.002394	-0.028729	9.796424	0.048230	0.086867	-0.037571
+1.468373	0.004788	-0.031123	9.786848	0.044233	0.086734	-0.037172
+1.469431	-0.035911	0.031123	9.844305	0.045165	0.083536	-0.034240
+1.470433	-0.014364	-0.004788	9.758119	0.046498	0.084735	-0.033175
+1.471435	0.002394	-0.028729	9.784454	0.046897	0.088599	-0.033974
+1.472433	0.026334	-0.031123	9.880215	0.048096	0.087000	-0.033175
+1.473438	0.016758	-0.031123	9.851487	0.047297	0.087133	-0.035173
+1.474404	0.007182	0.004788	9.839517	0.046364	0.085268	-0.034907
+1.475435	0.071821	-0.007182	9.880215	0.048096	0.086734	-0.037172
+1.476374	0.033517	0.014364	9.794030	0.047164	0.089665	-0.040103
+1.477398	0.019152	0.016758	9.841911	0.047830	0.088066	-0.040236
+1.478438	0.002394	-0.026334	9.813182	0.047697	0.087533	-0.035839
+1.479410	0.035911	0.031123	9.734179	0.045032	0.090198	-0.035306
+1.480439	0.038305	0.057457	9.707844	0.045432	0.089398	-0.037704
+1.481439	0.026334	-0.023940	9.825152	0.044632	0.085268	-0.037305
+1.482430	0.002394	0.000000	9.889792	0.045432	0.086201	-0.033308
+1.483438	0.035911	-0.021546	9.825152	0.047297	0.087933	-0.035440
+1.484368	-0.004788	0.023940	9.825152	0.045565	0.086734	-0.037172
+1.485408	0.000000	0.035911	9.846699	0.045565	0.084868	-0.038504
+1.486406	-0.009576	0.002394	9.832334	0.045432	0.085534	-0.032775
+1.487425	-0.014364	-0.028729	9.789242	0.047297	0.087266	-0.030643
+1.488437	-0.007182	-0.035911	9.777271	0.046364	0.087799	-0.033441
+1.489438	0.038305	-0.007182	9.832334	0.046231	0.088199	-0.034107
+1.490461	0.019152	0.011970	9.837123	0.047164	0.089798	-0.035839
+1.491432	0.019152	0.045487	9.817970	0.048096	0.087933	-0.037038
+1.492436	0.043093	-0.023940	9.837123	0.049562	0.087933	-0.038371
+1.493437	0.062245	-0.047881	9.870639	0.049029	0.085934	-0.036905
+1.494429	0.062245	-0.016758	9.851487	0.048629	0.088466	-0.035706
+1.495432	0.033517	-0.043093	9.765301	0.045698	0.089265	-0.035040
+1.496422	-0.002394	-0.016758	9.803606	0.046098	0.087799	-0.038237
+1.497454	0.023940	0.009576	9.762907	0.047031	0.087266	-0.036905
+1.498440	0.043093	-0.009576	9.841911	0.047164	0.086600	-0.038637
+1.499437	0.021546	0.007182	9.817970	0.048230	0.083669	-0.036106
+1.500434	0.019152	0.019152	9.794030	0.048896	0.084868	-0.033308
+1.501436	0.002394	0.011970	9.808394	0.050095	0.086734	-0.036106
+1.502410	-0.011970	-0.002394	9.817970	0.048096	0.083536	-0.039037
+1.503434	-0.021546	0.014364	9.827546	0.044899	0.085934	-0.038104
+1.504425	-0.055063	0.009576	9.815576	0.045299	0.088332	-0.038104
+1.505407	0.043093	-0.064639	9.913732	0.048363	0.087666	-0.037571
+1.506381	0.007182	-0.019152	9.882609	0.046897	0.086334	-0.038637
+1.507372	0.026334	-0.011970	9.875427	0.044632	0.086734	-0.036639
+1.508438	-0.014364	0.031123	9.849093	0.047164	0.087533	-0.033441
+1.509431	0.002394	0.052669	9.827546	0.048496	0.088199	-0.033974
+1.510436	-0.062245	0.016758	9.803606	0.049962	0.087000	-0.036106
+1.511409	-0.038305	0.026334	9.822758	0.048230	0.086467	-0.035573
+1.512371	0.050275	-0.007182	9.808394	0.047830	0.087533	-0.038770
+1.513357	0.047881	-0.019152	9.837123	0.047564	0.089132	-0.038904
+1.514388	-0.026334	0.038305	9.868245	0.045698	0.091397	-0.035040
+1.515434	-0.002394	0.059851	9.767695	0.046897	0.093528	-0.035173
+1.516446	0.004788	0.009576	9.736573	0.048363	0.090730	-0.036239
+1.517390	0.011970	-0.009576	9.832334	0.047031	0.086467	-0.039170
+1.518381	0.033517	0.000000	9.789242	0.045165	0.088066	-0.038237
+1.519371	0.057457	-0.047881	9.796424	0.046231	0.086867	-0.037305
+1.520436	-0.004788	-0.028729	9.796424	0.048230	0.085401	-0.035839
+1.521437	-0.014364	-0.007182	9.813182	0.046631	0.084469	-0.036505
+1.522438	0.031123	-0.007182	9.767695	0.044899	0.087266	-0.038637
+1.523437	0.031123	-0.023940	9.803606	0.045165	0.088998	-0.036372
+1.524375	0.019152	-0.016758	9.806000	0.045165	0.090331	-0.034507
+1.525430	-0.026334	-0.023940	9.750937	0.047031	0.089132	-0.037172
+1.526430	0.004788	-0.047881	9.786848	0.045965	0.087666	-0.038104
+1.527392	0.090974	-0.031123	9.841911	0.044499	0.088998	-0.038770
+1.528457	0.004788	0.000000	9.798818	0.045832	0.092063	-0.036772
+1.529437	0.016758	0.045487	9.750937	0.048496	0.089531	-0.033308
+1.530438	0.021546	-0.023940	9.786848	0.046098	0.088865	-0.032508
+1.531361	0.004788	0.000000	9.784454	0.046897	0.086600	-0.034640
+1.532437	-0.009576	-0.004788	9.791636	0.047164	0.086467	-0.038770
+1.533409	-0.045487	-0.009576	9.786848	0.045698	0.087000	-0.038770
+1.534410	0.040699	-0.009576	9.851487	0.044499	0.088332	-0.037838
+1.535392	-0.007182	-0.059851	9.808394	0.047830	0.089531	-0.033841
+1.536434	-0.016758	-0.043093	9.803606	0.049828	0.088199	-0.033441
+1.537437	0.019152	-0.031123	9.772483	0.046631	0.086201	-0.031176
+1.538436	-0.014364	-0.004788	9.695874	0.045565	0.086600	-0.033441
+1.539380	-0.009576	-0.038305	9.789242	0.046897	0.085801	-0.035440
+1.540431	-0.004788	-0.026334	9.777271	0.047963	0.084868	-0.035706
+1.541437	0.035911	-0.045487	9.698268	0.046364	0.086867	-0.033974
+1.542412	0.011970	0.021546	9.791636	0.045565	0.086334	-0.030776
+1.543433	0.016758	0.050275	9.760513	0.045032	0.085934	-0.034907
+1.544435	-0.009576	0.052669	9.774877	0.045565	0.084602	-0.035440
+1.545412	-0.019152	0.007182	9.873033	0.046631	0.086467	-0.036239
+1.546436	0.002394	0.028729	9.911338	0.048763	0.086867	-0.037838
+1.547434	0.055063	0.014364	9.875427	0.049429	0.087799	-0.035706
+1.548435	0.009576	-0.023940	9.923308	0.051294	0.086201	-0.035972
+1.549366	-0.011970	-0.052669	9.892186	0.049828	0.085268	-0.034240
+1.550432	-0.043093	-0.007182	9.853881	0.048096	0.086467	-0.033574
+1.551368	0.009576	-0.033517	9.858669	0.047297	0.087799	-0.031842
+1.552432	-0.016758	-0.038305	9.885003	0.046897	0.087533	-0.034640
+1.553410	0.028729	-0.007182	9.906550	0.046631	0.089931	-0.039037
+1.554360	0.023940	-0.035911	9.901762	0.047697	0.088599	-0.037305
+1.555434	0.014364	0.009576	9.786848	0.046631	0.090064	-0.036239
+1.556434	0.002394	0.000000	9.829940	0.044899	0.092462	-0.035573
+1.557433	-0.035911	-0.016758	9.846699	0.045299	0.090597	-0.034773
+1.558436	0.000000	-0.033517	9.813182	0.045432	0.089132	-0.035040
+1.559434	-0.019152	-0.016758	9.806000	0.046364	0.088865	-0.036372
+1.560362	0.040699	0.052669	9.822758	0.046631	0.089798	-0.036772
+1.561395	0.035911	0.035911	9.851487	0.044766	0.090597	-0.037571
+1.562437	0.035911	-0.038305	9.817970	0.046364	0.089265	-0.039703
+1.563369	-0.021546	-0.016758	9.738967	0.049162	0.086334	-0.038237
+1.564438	-0.023940	0.014364	9.844305	0.048629	0.089398	-0.036106
+1.565429	-0.016758	0.011970	9.861063	0.047297	0.089531	-0.036239
+1.566438	-0.021546	0.009576	9.853881	0.047297	0.086734	-0.036639
+1.567432	0.009576	-0.016758	9.829940	0.046764	0.085668	-0.036239
+1.568435	-0.007182	0.007182	9.806000	0.046364	0.088199	-0.037971
+1.569409	0.004788	-0.014364	9.767695	0.045299	0.086734	-0.037172
+1.570427	0.055063	-0.095762	9.798818	0.044632	0.084469	-0.037438
+1.571452	0.031123	-0.062245	9.707844	0.046631	0.085934	-0.035706
+1.572436	0.035911	0.004788	9.676722	0.046364	0.087799	-0.036639
+1.573438	0.002394	0.055063	9.765301	0.045299	0.090997	-0.039703
+1.574437	-0.019152	0.023940	9.820364	0.047963	0.090864	-0.039969
+1.575436	0.011970	-0.004788	9.844305	0.050095	0.088599	-0.037305
+1.576432	0.021546	-0.028729	9.829940	0.047564	0.088998	-0.036372
+1.577402	0.004788	-0.052669	9.784454	0.045432	0.089398	-0.036639
+1.578436	0.014364	-0.043093	9.698268	0.045299	0.088466	-0.037571
+1.579434	-0.002394	-0.055063	9.729391	0.047164	0.084069	-0.037172
+1.580406	-0.016758	0.009576	9.760513	0.048363	0.085135	-0.035573
+1.581398	-0.014364	0.014364	9.758119	0.049562	0.085934	-0.035306
+1.582438	0.009576	-0.016758	9.810788	0.045832	0.087533	-0.037038
+1.583434	-0.035911	0.014364	9.820364	0.045698	0.089798	-0.039303
+1.584366	-0.038305	0.004788	9.822758	0.047830	0.089798	-0.037704
+1.585336	0.002394	-0.045487	9.789242	0.048496	0.087799	-0.033708
+1.586369	0.028729	-0.004788	9.712632	0.048363	0.085668	-0.037172
+1.587375	-0.007182	-0.031123	9.782060	0.049029	0.085268	-0.038637
+1.588310	-0.035911	-0.031123	9.748543	0.047564	0.084335	-0.038504
+1.589371	-0.004788	-0.016758	9.791636	0.047164	0.085268	-0.033708
+1.590345	0.035911	0.033517	9.837123	0.046498	0.086067	-0.033841
+1.591345	0.047881	0.050275	9.794030	0.046631	0.086201	-0.033441
+1.592345	-0.004788	-0.004788	9.782060	0.044766	0.087666	-0.034240
+1.593351	0.004788	0.021546	9.796424	0.046631	0.088466	-0.036505
+1.594334	-0.002394	0.002394	9.808394	0.048629	0.089798	-0.036106
+1.595371	-0.019152	0.016758	9.834729	0.047963	0.091397	-0.036639
+1.596410	0.002394	-0.007182	9.791636	0.048230	0.089265	-0.039170
+1.597406	0.016758	-0.004788	9.791636	0.046364	0.086467	-0.038104
+1.598413	0.002394	0.023940	9.817970	0.047564	0.085934	-0.039303
+1.599410	0.033517	-0.019152	9.777271	0.045832	0.083270	-0.038104
+1.600371	0.016758	0.019152	9.827546	0.045432	0.085135	-0.037438
+1.601411	-0.035911	0.011970	9.700662	0.046498	0.088066	-0.036106
+1.602429	0.023940	-0.028729	9.789242	0.047430	0.088332	-0.041035
+1.603412	-0.011970	-0.059851	9.817970	0.048363	0.085934	-0.037038
+1.604450	0.000000	-0.069427	9.782060	0.047830	0.088599	-0.036239
+1.605459	0.009576	-0.031123	9.726997	0.046897	0.087533	-0.036239
+1.606463	0.000000	-0.021546	9.877821	0.047830	0.087533	-0.034107
+1.607461	0.031123	0.019152	9.806000	0.048496	0.087400	-0.036372
+1.608411	-0.007182	0.009576	9.767695	0.050628	0.087933	-0.037305
+1.609460	-0.040699	0.023940	9.810788	0.049429	0.089265	-0.034507
+1.610394	-0.021546	0.028729	9.810788	0.046764	0.089265	-0.036372
+1.611458	-0.098156	-0.002394	9.779666	0.045565	0.089931	-0.039703
+1.612391	-0.043093	-0.079003	9.789242	0.045565	0.088998	-0.040369
+1.613420	-0.031123	-0.035911	9.815576	0.047564	0.088199	-0.035306
+1.614392	0.002394	0.021546	9.767695	0.045965	0.089398	-0.035839
+1.615457	-0.007182	0.050275	9.858669	0.045832	0.087666	-0.038504
+1.616457	0.019152	0.011970	9.880215	0.046764	0.087533	-0.037838
+1.617456	0.028729	-0.043093	9.789242	0.047430	0.088466	-0.035306
+1.618397	-0.023940	-0.035911	9.806000	0.046231	0.089798	-0.035440
+1.619416	-0.059851	0.011970	9.796424	0.046498	0.086734	-0.039303
+1.620458	-0.079003	-0.019152	9.784454	0.048763	0.086467	-0.037704
+1.621417	-0.057457	-0.026334	9.853881	0.048896	0.088466	-0.037038
+1.622392	-0.021546	-0.021546	9.832334	0.046231	0.088732	-0.035839
+1.623450	-0.055063	-0.004788	9.782060	0.045165	0.088066	-0.036239
+1.624458	0.011970	-0.011970	9.829940	0.043833	0.086067	-0.037172
+1.625410	0.021546	-0.019152	9.885003	0.044632	0.084735	-0.033574
+1.626461	0.028729	0.033517	9.853881	0.046764	0.088199	-0.033574
+1.627461	0.007182	-0.009576	9.815576	0.047297	0.087933	-0.035173
+1.628455	0.081397	0.043093	9.758119	0.047031	0.086600	-0.037172
+1.629459	0.074215	0.002394	9.803606	0.046098	0.086867	-0.033841
+1.630413	0.021546	-0.009576	9.849093	0.046631	0.086867	-0.034107
+1.631423	0.019152	0.004788	9.825152	0.046364	0.085668	-0.035706
+1.632460	0.016758	0.035911	9.877821	0.046764	0.089531	-0.036772
+1.633459	0.000000	0.038305	9.777271	0.049162	0.089132	-0.035972
+1.634414	0.026334	-0.028729	9.841911	0.047164	0.083936	-0.035306
+1.635392	0.004788	-0.028729	9.849093	0.046764	0.084735	-0.033308
+1.636456	-0.026334	0.000000	9.753331	0.046631	0.088066	-0.032642
+1.637412	0.011970	0.009576	9.820364	0.045832	0.087666	-0.031309
+1.638388	-0.016758	-0.026334	9.770089	0.045698	0.088599	-0.035173
+1.639386	-0.033517	-0.031123	9.719814	0.046098	0.090198	-0.036106
+1.640365	-0.023940	-0.028729	9.758119	0.046897	0.091263	-0.039436
+1.641387	-0.033517	0.023940	9.846699	0.045832	0.091130	-0.039570
+1.642387	-0.011970	0.026334	9.853881	0.045832	0.088998	-0.036772
+1.643386	-0.014364	-0.040699	9.825152	0.046231	0.089265	-0.035573
+1.644385	-0.007182	-0.040699	9.786848	0.046897	0.090198	-0.037838
+1.645384	0.000000	0.014364	9.789242	0.047697	0.089265	-0.037571
+1.646321	-0.019152	0.011970	9.784454	0.047164	0.088732	-0.036905
+1.647300	0.007182	0.019152	9.803606	0.045032	0.088732	-0.036239
+1.648320	0.028729	-0.040699	9.834729	0.044766	0.090198	-0.036239
+1.649320	0.088580	-0.011970	9.762907	0.045698	0.089398	-0.040502
+1.650320	0.035911	-0.033517	9.803606	0.044766	0.086734	-0.039170
+1.651319	-0.016758	0.002394	9.810788	0.043167	0.085401	-0.034107
+1.652319	-0.047881	0.016758	9.777271	0.047830	0.086734	-0.033841
+1.653319	-0.011970	-0.014364	9.837123	0.049162	0.086067	-0.035972
+1.654319	-0.004788	-0.023940	9.844305	0.048763	0.087666	-0.034907
+1.655320	-0.040699	-0.016758	9.765301	0.046764	0.090597	-0.035706
+1.656319	-0.004788	0.016758	9.767695	0.045698	0.091130	-0.039436
+1.657325	0.064639	0.062245	9.789242	0.045165	0.090464	-0.039436
+1.658331	0.011970	0.059851	9.743755	0.045698	0.091796	-0.036239
+1.659321	-0.002394	0.062245	9.801212	0.047963	0.089265	-0.036372
+1.660325	-0.002394	0.004788	9.822758	0.047297	0.087933	-0.036639
+1.661320	0.004788	-0.045487	9.789242	0.045565	0.088599	-0.034773
+1.662321	-0.002394	-0.033517	9.736573	0.042501	0.086867	-0.034507
+1.663315	0.079003	-0.055063	9.817970	0.045032	0.087266	-0.035173
+1.664325	0.038305	-0.019152	9.892186	0.046897	0.088199	-0.038637
+1.665316	0.014364	-0.028729	9.772483	0.050495	0.088066	-0.036505
+1.666320	0.014364	-0.011970	9.731785	0.050495	0.087533	-0.035040
+1.667315	0.011970	0.019152	9.743755	0.046764	0.087533	-0.037038
+1.668318	-0.031123	-0.055063	9.806000	0.043833	0.088066	-0.036372
+1.669314	-0.071821	0.004788	9.889792	0.045299	0.085934	-0.038637
+1.670319	0.009576	0.043093	9.851487	0.049296	0.086067	-0.040236
+1.671319	0.007182	-0.002394	9.815576	0.049429	0.086201	-0.037838
+1.672319	-0.057457	-0.067033	9.791636	0.048629	0.086867	-0.036106
+1.673337	-0.026334	-0.069427	9.865851	0.047297	0.088332	-0.037305
+1.674301	0.011970	0.031123	9.782060	0.045299	0.090331	-0.035040
+1.675336	-0.021546	0.026334	9.844305	0.047297	0.091130	-0.031975
+1.676319	0.031123	-0.023940	9.875427	0.047164	0.089798	-0.036505
+1.677315	0.014364	-0.011970	9.906550	0.045165	0.086467	-0.039703
+1.678319	-0.028729	-0.040699	9.877821	0.044766	0.085268	-0.039570
+1.679318	0.007182	-0.009576	9.806000	0.044499	0.089265	-0.036905
+1.680319	0.052669	-0.019152	9.846699	0.046364	0.088199	-0.037571
+1.681319	0.035911	0.000000	9.882609	0.046631	0.087000	-0.037704
+1.682318	0.043093	0.028729	9.894580	0.046631	0.087400	-0.035040
+1.683318	0.069427	0.019152	9.868245	0.047031	0.087000	-0.035306
+1.684318	0.055063	-0.023940	9.832334	0.047297	0.085934	-0.036505
+1.685319	0.052669	-0.016758	9.779666	0.045698	0.087133	-0.038904
+1.686318	0.069427	0.050275	9.849093	0.045965	0.088732	-0.039836
+1.687318	0.031123	0.004788	9.801212	0.047430	0.088599	-0.036106
+1.688315	0.014364	0.000000	9.777271	0.046231	0.086600	-0.030377
+1.689349	0.031123	0.011970	9.736573	0.044499	0.085668	-0.035839
+1.690319	0.081397	-0.016758	9.863457	0.043700	0.085002	-0.036106
+1.691316	0.052669	-0.047881	9.846699	0.044632	0.087133	-0.039170
+1.692314	0.047881	-0.050275	9.750937	0.046498	0.087266	-0.038504
+1.693318	0.021546	-0.031123	9.777271	0.046098	0.088599	-0.037305
+1.694319	0.028729	0.043093	9.846699	0.046364	0.089265	-0.036106
+1.695335	0.016758	0.004788	9.810788	0.047697	0.089398	-0.034640
+1.696393	-0.038305	-0.007182	9.782060	0.047164	0.088332	-0.036772
+1.697386	-0.035911	-0.011970	9.753331	0.046631	0.087000	-0.036239
+1.698347	0.011970	-0.014364	9.715026	0.048496	0.086734	-0.034507
+1.699346	0.076609	-0.057457	9.782060	0.047830	0.087666	-0.033841
+1.700378	0.071821	-0.047881	9.782060	0.045698	0.090730	-0.033574
+1.701352	0.038305	-0.028729	9.822758	0.046364	0.090597	-0.036905
+1.702375	0.011970	-0.033517	9.849093	0.046631	0.086734	-0.037704
+1.703339	0.009576	-0.026334	9.798818	0.046764	0.084469	-0.033175
+1.704336	0.023940	-0.100550	9.765301	0.045565	0.084602	-0.035306
+1.705349	0.002394	0.016758	9.741361	0.043833	0.087799	-0.038637
+1.706348	-0.031123	0.014364	9.729391	0.042767	0.087799	-0.039703
+1.707317	0.019152	-0.007182	9.729391	0.047430	0.088066	-0.036239
+1.708394	0.023940	-0.031123	9.762907	0.049962	0.087799	-0.033574
+1.709400	0.016758	0.004788	9.750937	0.047430	0.083669	-0.033441
+1.710327	0.028729	-0.035911	9.796424	0.044766	0.086600	-0.035040
+1.711359	-0.002394	0.000000	9.755725	0.045299	0.087533	-0.035040
+1.712384	-0.004788	-0.007182	9.753331	0.048096	0.089132	-0.037438
+1.713337	0.009576	-0.031123	9.806000	0.047697	0.091130	-0.034107
+1.714321	0.026334	-0.057457	9.839517	0.047297	0.089798	-0.033574
+1.715398	0.004788	-0.033517	9.827546	0.047697	0.086600	-0.032908
+1.716349	0.019152	-0.009576	9.839517	0.046498	0.086334	-0.035306
+1.717391	0.004788	0.002394	9.789242	0.045432	0.088732	-0.038504
+1.718361	-0.052669	0.004788	9.791636	0.047031	0.087666	-0.039170
+1.719407	0.023940	0.035911	9.774877	0.047031	0.086734	-0.036772
+1.720393	0.040699	0.014364	9.810788	0.048496	0.088066	-0.035173
+1.721352	-0.038305	-0.021546	9.877821	0.049562	0.089531	-0.032375
+1.722393	0.038305	-0.031123	9.889792	0.047297	0.090864	-0.032642
+1.723399	0.059851	-0.033517	9.841911	0.045832	0.088332	-0.039037
+1.724388	-0.002394	-0.004788	9.810788	0.047164	0.086467	-0.041568
+1.725397	0.038305	0.009576	9.806000	0.047297	0.087400	-0.040369
+1.726396	0.016758	-0.050275	9.832334	0.047430	0.088865	-0.038371
+1.727397	0.002394	-0.083792	9.774877	0.047430	0.089132	-0.034507
+1.728398	0.009576	-0.040699	9.760513	0.045698	0.089531	-0.035839
+1.729399	0.002394	0.021546	9.779666	0.045032	0.089931	-0.034507
+1.730399	0.004788	0.016758	9.832334	0.046098	0.088466	-0.035440
+1.731392	0.021546	0.035911	9.820364	0.047430	0.087666	-0.037305
+1.732397	0.021546	0.011970	9.796424	0.047297	0.089132	-0.038104
+1.733396	0.007182	-0.038305	9.829940	0.047430	0.087799	-0.038371
+1.734371	0.040699	-0.064639	9.815576	0.047564	0.085801	-0.032908
+1.735394	0.067033	-0.026334	9.808394	0.047164	0.085268	-0.032375
+1.736325	0.019152	-0.021546	9.806000	0.045565	0.088998	-0.034640
+1.737395	-0.057457	-0.021546	9.820364	0.043833	0.091796	-0.036639
+1.738398	-0.019152	0.011970	9.846699	0.047031	0.091663	-0.037438
+1.739393	0.007182	-0.045487	9.846699	0.050761	0.088599	-0.037704
+1.740397	0.016758	-0.014364	9.729391	0.051028	0.087799	-0.037172
+1.741369	-0.035911	0.035911	9.753331	0.047564	0.088732	-0.041701
+1.742397	-0.004788	0.009576	9.770089	0.044899	0.088066	-0.038104
+1.743391	0.057457	-0.043093	9.834729	0.047031	0.088199	-0.035173
+1.744358	0.023940	-0.038305	9.784454	0.049828	0.086600	-0.033441
+1.745393	0.050275	0.045487	9.729391	0.048763	0.087000	-0.032775
+1.746396	-0.007182	0.059851	9.928096	0.047031	0.088732	-0.034773
+1.747400	-0.007182	0.071821	9.849093	0.045165	0.091397	-0.034507
+1.748400	-0.019152	-0.009576	9.810788	0.045032	0.091397	-0.038371
+1.749398	0.000000	-0.047881	9.734179	0.045965	0.088732	-0.038504
+1.750339	0.011970	-0.019152	9.758119	0.046098	0.087400	-0.036639
+1.751398	0.004788	0.002394	9.803606	0.046231	0.087666	-0.033708
+1.752399	0.021546	-0.007182	9.760513	0.048096	0.087799	-0.032775
+1.753393	-0.014364	0.009576	9.777271	0.049695	0.085934	-0.034107
+1.754331	-0.038305	-0.031123	9.813182	0.046498	0.085401	-0.037305
+1.755398	0.000000	-0.047881	9.820364	0.044766	0.088066	-0.037838
+1.756391	0.009576	-0.009576	9.803606	0.045832	0.087933	-0.035040
+1.757395	0.021546	-0.019152	9.825152	0.045299	0.085268	-0.036505
+1.758399	-0.009576	-0.045487	9.899368	0.045698	0.086201	-0.036772
+1.759397	0.021546	-0.021546	9.825152	0.045432	0.089665	-0.036372
+1.760398	-0.009576	-0.016758	9.784454	0.045432	0.087666	-0.035040
+1.761398	0.021546	-0.011970	9.791636	0.047297	0.088199	-0.035173
+1.762395	0.021546	-0.011970	9.746149	0.045698	0.087133	-0.039436
+1.763382	0.007182	-0.067033	9.782060	0.046231	0.087133	-0.036505
+1.764353	0.002394	-0.071821	9.844305	0.046631	0.087666	-0.032375
+1.765370	-0.014364	0.000000	9.887397	0.046764	0.088732	-0.035972
+1.766396	0.000000	0.009576	9.844305	0.047164	0.086867	-0.035306
+1.767349	-0.007182	-0.014364	9.794030	0.047697	0.086600	-0.035173
+1.768310	-0.040699	-0.023940	9.791636	0.049296	0.090597	-0.034773
+1.769383	0.002394	-0.062245	9.762907	0.047164	0.090331	-0.036505
+1.770399	0.000000	-0.040699	9.770089	0.047697	0.087133	-0.035706
+1.771396	0.002394	-0.014364	9.873033	0.045965	0.086334	-0.036505
+1.772367	0.026334	0.014364	9.899368	0.047297	0.087666	-0.035706
+1.773398	0.011970	0.023940	9.882609	0.046764	0.086067	-0.037038
+1.774389	-0.014364	-0.011970	9.849093	0.045832	0.085934	-0.035173
+1.775356	-0.011970	-0.045487	9.796424	0.044899	0.085668	-0.033574
+1.776330	0.009576	-0.033517	9.760513	0.044766	0.085801	-0.036639
+1.777365	-0.009576	-0.021546	9.820364	0.045698	0.087133	-0.038904
+1.778338	0.069427	-0.014364	9.801212	0.048629	0.087266	-0.035040
+1.779398	0.043093	-0.059851	9.815576	0.048096	0.087533	-0.034773
+1.780400	0.021546	-0.052669	9.920914	0.047164	0.084735	-0.035706
+1.781396	-0.002394	0.000000	9.873033	0.048629	0.084202	-0.033974
+1.782421	-0.011970	-0.004788	9.820364	0.047564	0.087266	-0.036505
+1.783455	-0.031123	-0.028729	9.820364	0.046764	0.089398	-0.037038
+1.784420	-0.014364	0.016758	9.853881	0.045165	0.089665	-0.034640
+1.785392	0.009576	0.009576	9.851487	0.045565	0.087933	-0.037571
+1.786423	0.090974	0.026334	9.794030	0.043966	0.084868	-0.037838
+1.787455	0.011970	-0.023940	9.772483	0.044632	0.085534	-0.037305
+1.788457	0.000000	-0.014364	9.825152	0.045698	0.085002	-0.036905
+1.789456	-0.023940	-0.007182	9.765301	0.048363	0.085668	-0.037038
+1.790460	-0.009576	-0.019152	9.734179	0.048896	0.088332	-0.034640
+1.791401	-0.009576	0.011970	9.724603	0.047297	0.090597	-0.036639
+1.792362	-0.002394	0.031123	9.746149	0.048230	0.089665	-0.037571
+1.793359	-0.064639	0.000000	9.700662	0.048096	0.088865	-0.035839
+1.794332	-0.038305	-0.028729	9.827546	0.045565	0.088332	-0.036905
+1.795322	0.009576	0.031123	9.791636	0.046764	0.089531	-0.035173
+1.796345	0.033517	-0.023940	9.877821	0.048230	0.090997	-0.034374
+1.797385	-0.007182	-0.014364	9.885003	0.047164	0.089531	-0.037305
+1.798385	0.004788	0.011970	9.841911	0.046631	0.089531	-0.037305
+1.799382	-0.045487	-0.026334	9.827546	0.046897	0.088998	-0.038371
+1.800382	0.004788	0.021546	9.772483	0.045299	0.088332	-0.037438
+1.801362	0.026334	0.040699	9.829940	0.044899	0.090198	-0.039436
+1.802377	0.021546	0.031123	9.755725	0.046764	0.089398	-0.037038
+1.803383	-0.038305	-0.019152	9.786848	0.048096	0.086467	-0.035040
+1.804368	0.000000	0.011970	9.784454	0.047031	0.087000	-0.036905
+1.805384	0.038305	-0.004788	9.772483	0.046764	0.087933	-0.037971
+1.806389	0.098156	-0.002394	9.784454	0.045565	0.087533	-0.038237
+1.807409	0.045487	-0.023940	9.832334	0.046631	0.085801	-0.037172
+1.808411	-0.002394	0.016758	9.810788	0.047430	0.086467	-0.038637
+1.809400	-0.014364	0.026334	9.813182	0.048896	0.088466	-0.039436
+1.810459	-0.009576	-0.007182	9.753331	0.048096	0.090464	-0.036106
+1.811424	0.000000	-0.011970	9.779666	0.045698	0.089931	-0.035839
+1.812412	0.023940	-0.057457	9.834729	0.045965	0.088332	-0.036505
+1.813454	0.026334	-0.023940	9.911338	0.047963	0.086334	-0.035573
+1.814376	0.026334	-0.007182	9.813182	0.048763	0.083936	-0.034507
+1.815389	0.081397	-0.009576	9.784454	0.050361	0.083669	-0.036372
+1.816382	0.004788	0.031123	9.825152	0.047830	0.084069	-0.036239
+1.817413	0.019152	0.000000	9.820364	0.047564	0.087533	-0.037438
+1.818458	-0.055063	0.007182	9.844305	0.048763	0.089931	-0.034640
+1.819471	-0.033517	0.033517	9.849093	0.046498	0.089931	-0.033841
+1.820459	-0.057457	0.004788	9.806000	0.045032	0.087799	-0.036505
+1.821454	-0.090974	-0.019152	9.829940	0.043700	0.085801	-0.040369
+1.822462	-0.011970	0.014364	9.868245	0.045165	0.087533	-0.035173
+1.823458	-0.028729	-0.055063	9.865851	0.048230	0.087533	-0.031842
+1.824415	-0.038305	-0.026334	9.861063	0.047830	0.087133	-0.033041
+1.825425	0.004788	-0.095762	9.829940	0.048096	0.088998	-0.035706
+1.826412	0.040699	-0.148431	9.815576	0.050361	0.089265	-0.038104
+1.827454	0.050275	-0.035911	9.892186	0.048096	0.087666	-0.036106
+1.828455	0.033517	0.071821	9.892186	0.044766	0.085668	-0.035306
+1.829456	-0.014364	0.035911	9.712632	0.045032	0.086867	-0.034773
+1.830459	-0.021546	-0.002394	9.717420	0.046764	0.089132	-0.035706
+1.831455	-0.023940	0.009576	9.693480	0.048096	0.088732	-0.035972
+1.832457	-0.016758	0.035911	9.789242	0.048496	0.086467	-0.035306
+1.833458	0.016758	0.031123	9.882609	0.048496	0.085801	-0.033841
+1.834410	0.016758	0.000000	9.822758	0.047963	0.086867	-0.033708
+1.835393	0.026334	0.023940	9.822758	0.047963	0.087000	-0.036772
+1.836453	0.021546	0.019152	9.772483	0.048496	0.087933	-0.035040
+1.837457	-0.021546	0.014364	9.803606	0.048896	0.089398	-0.036239
+1.838459	-0.055063	-0.038305	9.774877	0.045565	0.090064	-0.036905
+1.839455	-0.007182	-0.067033	9.801212	0.045299	0.088199	-0.033708
+1.840455	-0.016758	-0.050275	9.794030	0.046231	0.086867	-0.032775
+1.841455	0.002394	-0.011970	9.863457	0.047164	0.088066	-0.032109
+1.842455	0.031123	0.000000	9.803606	0.048363	0.090597	-0.033041
+1.843411	0.019152	-0.040699	9.806000	0.046631	0.090198	-0.035972
+1.844416	0.004788	-0.035911	9.782060	0.047297	0.089265	-0.036372
+1.845456	-0.045487	-0.014364	9.779666	0.047697	0.087400	-0.035706
+1.846458	-0.004788	-0.016758	9.841911	0.046364	0.085801	-0.034240
+1.847455	-0.026334	0.011970	9.837123	0.047430	0.086067	-0.035040
+1.848455	-0.040699	0.000000	9.849093	0.048896	0.087666	-0.037704
+1.849413	0.026334	0.007182	9.837123	0.048763	0.089398	-0.038504
+1.850455	-0.002394	-0.035911	9.829940	0.048896	0.090864	-0.037305
+1.851419	-0.031123	-0.004788	9.820364	0.047430	0.090331	-0.036905
+1.852396	0.009576	0.009576	9.753331	0.045565	0.089798	-0.036106
+1.853412	-0.002394	0.009576	9.767695	0.046098	0.089531	-0.039037
+1.854459	0.007182	0.014364	9.798818	0.044899	0.089398	-0.038237
+1.855455	-0.011970	-0.019152	9.746149	0.044899	0.090597	-0.038904
+1.856453	-0.014364	0.011970	9.786848	0.046764	0.089531	-0.040236
+1.857455	0.023940	-0.038305	9.810788	0.046764	0.089398	-0.038104
+1.858413	0.004788	-0.009576	9.849093	0.046231	0.088466	-0.038237
+1.859454	-0.004788	0.016758	9.834729	0.045698	0.088865	-0.037438
+1.860454	-0.083792	-0.067033	9.796424	0.044366	0.086600	-0.035573
+1.861414	-0.057457	-0.052669	9.762907	0.045299	0.086334	-0.035173
+1.862433	-0.004788	-0.021546	9.822758	0.045698	0.086734	-0.035306
+1.863455	-0.007182	0.004788	9.870639	0.047564	0.086067	-0.038371
+1.864393	-0.033517	-0.016758	9.844305	0.045698	0.088998	-0.037038
+1.865371	0.004788	-0.002394	9.853881	0.047430	0.090331	-0.036372
+1.866359	-0.026334	-0.011970	9.796424	0.044899	0.089665	-0.037838
+1.867389	-0.016758	-0.016758	9.870639	0.044366	0.089931	-0.037971
+1.868405	0.019152	-0.004788	9.858669	0.043966	0.089132	-0.037571
+1.869392	0.002394	-0.023940	9.829940	0.044766	0.089531	-0.035440
+1.870455	-0.031123	-0.019152	9.772483	0.046231	0.091663	-0.036239
+1.871391	-0.033517	0.043093	9.750937	0.050361	0.088466	-0.035173
+1.872454	0.002394	0.045487	9.796424	0.048896	0.086067	-0.036639
+1.873455	0.014364	0.000000	9.851487	0.045565	0.085401	-0.037571
+1.874410	0.016758	0.009576	9.748543	0.044499	0.083936	-0.035573
+1.875453	-0.014364	0.016758	9.750937	0.043833	0.085534	-0.038904
+1.876370	-0.011970	0.052669	9.789242	0.045165	0.087000	-0.038237
+1.877447	0.009576	0.007182	9.863457	0.044366	0.090064	-0.036772
+1.878455	-0.014364	-0.040699	9.911338	0.045032	0.090864	-0.036505
+1.879454	0.052669	-0.064639	9.815576	0.046231	0.090597	-0.033441
+1.880414	0.019152	-0.040699	9.815576	0.046897	0.089398	-0.032242
+1.881423	0.026334	0.023940	9.829940	0.046364	0.087266	-0.035972
+1.882461	0.016758	-0.009576	9.844305	0.046364	0.086067	-0.040236
+1.883452	0.062245	0.023940	9.782060	0.047830	0.085002	-0.036239
+1.884454	0.040699	0.040699	9.801212	0.046498	0.088066	-0.032642
+1.885396	0.004788	0.009576	9.856275	0.046231	0.091263	-0.033175
+1.886384	-0.016758	0.002394	9.815576	0.047830	0.089531	-0.035839
+1.887389	0.067033	0.016758	9.782060	0.048230	0.085002	-0.038237
+1.888389	0.016758	-0.011970	9.877821	0.046631	0.085268	-0.037971
+1.889390	-0.028729	-0.026334	9.834729	0.045965	0.088865	-0.037438
+1.890383	0.019152	-0.009576	9.779666	0.044899	0.090198	-0.037305
+1.891451	0.019152	0.011970	9.801212	0.045832	0.089265	-0.037038
+1.892454	0.026334	0.021546	9.803606	0.045165	0.086734	-0.038371
+1.893453	0.000000	0.009576	9.770089	0.044233	0.085135	-0.039703
+1.894411	-0.023940	0.031123	9.743755	0.045965	0.088066	-0.039037
+1.895410	0.093368	-0.026334	9.765301	0.047564	0.089398	-0.036106
+1.896453	0.009576	-0.047881	9.784454	0.048096	0.089132	-0.035972
+1.897387	-0.059851	-0.011970	9.789242	0.046897	0.087400	-0.038904
+1.898394	0.004788	0.014364	9.794030	0.045832	0.087533	-0.036905
+1.899452	0.011970	0.000000	9.794030	0.044899	0.085668	-0.039969
+1.900353	0.000000	-0.007182	9.853881	0.043833	0.086201	-0.039037
+1.901421	0.040699	0.002394	9.779666	0.045565	0.086600	-0.039037
+1.902460	0.052669	0.033517	9.777271	0.047031	0.087666	-0.037838
+1.903458	-0.002394	0.002394	9.832334	0.050095	0.086334	-0.035839
+1.904454	-0.023940	0.031123	9.882609	0.049029	0.085534	-0.032775
+1.905456	-0.021546	0.004788	9.863457	0.045698	0.087266	-0.033841
+1.906459	0.007182	-0.062245	9.810788	0.046231	0.087533	-0.035573
+1.907455	0.062245	-0.031123	9.839517	0.046631	0.087133	-0.036905
+1.908453	-0.007182	0.000000	9.789242	0.046764	0.086067	-0.037704
+1.909420	-0.019152	-0.021546	9.813182	0.047297	0.089798	-0.038904
+1.910378	-0.004788	-0.004788	9.887397	0.047830	0.087266	-0.037305
+1.911406	0.011970	0.028729	9.794030	0.045565	0.088199	-0.032642
+1.912396	0.021546	-0.004788	9.762907	0.044366	0.088466	-0.036106
+1.913456	-0.011970	-0.028729	9.734179	0.045565	0.087000	-0.039170
+1.914383	-0.033517	0.028729	9.760513	0.047430	0.087133	-0.038904
+1.915386	-0.074215	-0.004788	9.717420	0.048763	0.084735	-0.040236
+1.916392	-0.028729	-0.004788	9.717420	0.048763	0.085135	-0.039836
+1.917388	-0.050275	-0.002394	9.748543	0.047031	0.087533	-0.035440
+1.918361	0.004788	-0.047881	9.710238	0.046498	0.088199	-0.036905
+1.919355	0.021546	-0.023940	9.758119	0.047297	0.088332	-0.039703
+1.920354	-0.014364	-0.002394	9.853881	0.047564	0.088199	-0.037571
+1.921359	0.093368	-0.021546	9.834729	0.046897	0.090331	-0.036639
+1.922305	0.031123	0.052669	9.882609	0.047031	0.089265	-0.038237
+1.923299	0.026334	-0.028729	9.901762	0.046897	0.085668	-0.038904
+1.924307	0.009576	-0.004788	9.837123	0.047164	0.087400	-0.039436
+1.925353	0.031123	0.000000	9.841911	0.046098	0.089798	-0.038104
+1.926392	-0.021546	0.019152	9.770089	0.044632	0.088199	-0.037305
+1.927394	-0.059851	-0.014364	9.794030	0.048096	0.086867	-0.035306
+1.928394	0.007182	-0.026334	9.870639	0.050495	0.087799	-0.035972
+1.929396	0.028729	-0.038305	9.853881	0.049296	0.088998	-0.037038
+1.930395	0.052669	0.031123	9.829940	0.045299	0.088332	-0.035306
+1.931393	-0.007182	-0.011970	9.834729	0.045565	0.086867	-0.035706
+1.932392	-0.016758	-0.004788	9.760513	0.047164	0.087666	-0.036239
+1.933388	-0.074215	-0.016758	9.861063	0.048096	0.086867	-0.034240
+1.934371	-0.016758	-0.047881	9.906550	0.048629	0.086734	-0.037571
+1.935324	0.011970	-0.062245	9.803606	0.047830	0.086067	-0.037704
+1.936341	0.040699	-0.002394	9.827546	0.048763	0.086067	-0.038371
+1.937329	0.007182	0.014364	9.930490	0.049162	0.087266	-0.039969
+1.938352	0.004788	0.045487	9.810788	0.047297	0.090597	-0.035040
+1.939347	0.004788	0.035911	9.822758	0.045299	0.090864	-0.034773
+1.940394	0.009576	0.016758	9.791636	0.046231	0.088865	-0.035839
+1.941393	0.028729	0.033517	9.741361	0.047297	0.085401	-0.038637
+1.942397	-0.009576	0.031123	9.770089	0.048230	0.085534	-0.039303
+1.943392	0.038305	-0.009576	9.782060	0.045698	0.085534	-0.032908
+1.944366	0.009576	0.011970	9.870639	0.044632	0.087133	-0.035706
+1.945394	0.035911	-0.016758	9.825152	0.049029	0.087266	-0.037438
+1.946345	0.043093	0.038305	9.834729	0.050228	0.086867	-0.036772
+1.947379	0.000000	0.002394	9.772483	0.048763	0.085668	-0.036372
+1.948355	0.050275	-0.083792	9.741361	0.048096	0.083536	-0.036772
+1.949414	0.059851	-0.031123	9.791636	0.047963	0.086467	-0.035706
+1.950353	0.023940	0.038305	9.817970	0.046498	0.087933	-0.035706
+1.951345	-0.009576	0.016758	9.748543	0.048096	0.087133	-0.037038
+1.952394	0.021546	0.021546	9.762907	0.046764	0.088066	-0.037305
+1.953395	0.000000	0.043093	9.765301	0.043567	0.090730	-0.036505
+1.954396	-0.023940	0.023940	9.789242	0.046498	0.090064	-0.034240
+1.955388	-0.028729	0.040699	9.789242	0.050628	0.088732	-0.036106
+1.956394	-0.023940	0.014364	9.853881	0.051560	0.086600	-0.037704
+1.957392	-0.028729	0.007182	9.892186	0.048629	0.086334	-0.038770
+1.958364	0.000000	-0.004788	9.868245	0.046631	0.085401	-0.035972
+1.959360	0.016758	0.021546	9.846699	0.047830	0.087799	-0.035573
+1.960392	-0.016758	0.004788	9.849093	0.047430	0.088466	-0.037838
+1.961393	-0.045487	0.000000	9.834729	0.047430	0.088865	-0.038637
+1.962395	0.004788	0.009576	9.801212	0.047564	0.091263	-0.037971
+1.963394	0.095762	-0.033517	9.729391	0.045832	0.090597	-0.035440
+1.964384	0.038305	-0.019152	9.794030	0.047430	0.087400	-0.035573
+1.965392	-0.009576	0.004788	9.782060	0.046897	0.086600	-0.037571
+1.966347	0.019152	-0.033517	9.808394	0.046231	0.089132	-0.034507
+1.967337	0.033517	-0.043093	9.825152	0.047564	0.088865	-0.034907
+1.968387	0.035911	-0.035911	9.839517	0.046897	0.086334	-0.035040
+1.969395	0.028729	0.055063	9.832334	0.047297	0.086334	-0.037838
+1.970341	0.050275	0.011970	9.832334	0.045032	0.087666	-0.037838
+1.971394	-0.002394	0.007182	9.820364	0.045165	0.088332	-0.036505
+1.972395	0.016758	0.033517	9.782060	0.048363	0.088466	-0.037305
+1.973388	0.031123	0.000000	9.803606	0.051028	0.090464	-0.038504
+1.974337	0.028729	-0.047881	9.813182	0.049562	0.092329	-0.035040
+1.975395	0.052669	-0.031123	9.734179	0.047564	0.090064	-0.035839
+1.976392	0.055063	0.009576	9.719814	0.047697	0.088865	-0.033841
+1.977379	0.035911	0.019152	9.743755	0.048763	0.088466	-0.031309
+1.978392	-0.023940	-0.023940	9.815576	0.045565	0.086734	-0.033841
+1.979373	-0.016758	-0.014364	9.779666	0.047297	0.084602	-0.037971
+1.980410	-0.004788	0.016758	9.806000	0.048096	0.085401	-0.036772
+1.981388	-0.035911	0.004788	9.803606	0.047830	0.088199	-0.035173
+1.982397	-0.014364	-0.014364	9.722208	0.047564	0.088732	-0.036905
+1.983391	0.002394	-0.009576	9.827546	0.049429	0.086867	-0.037305
+1.984387	-0.004788	0.019152	9.825152	0.048896	0.087533	-0.035706
+1.985345	-0.007182	-0.028729	9.853881	0.046764	0.086734	-0.036905
+1.986392	-0.028729	-0.052669	9.789242	0.047297	0.085801	-0.036905
+1.987394	-0.031123	0.000000	9.832334	0.046897	0.090198	-0.033041
+1.988391	0.021546	0.043093	9.858669	0.046897	0.090997	-0.035040
+1.989382	0.069427	-0.021546	9.892186	0.049962	0.090730	-0.035306
+1.990395	0.009576	-0.083792	9.829940	0.049828	0.088066	-0.035306
+1.991395	-0.019152	-0.052669	9.798818	0.047564	0.086734	-0.038237
+1.992394	0.040699	-0.004788	9.731785	0.047297	0.084735	-0.036372
+1.993395	0.064639	-0.004788	9.784454	0.047830	0.085401	-0.036239
+1.994396	-0.009576	-0.004788	9.741361	0.047697	0.089665	-0.038770
+1.995392	-0.023940	-0.009576	9.813182	0.045965	0.091530	-0.034907
+1.996394	-0.019152	-0.026334	9.858669	0.045032	0.090064	-0.033175
+1.997392	0.057457	-0.004788	9.829940	0.044499	0.089665	-0.033841
+1.998392	0.002394	0.014364	9.770089	0.044100	0.089132	-0.036905
+1.999380	0.021546	0.023940	9.770089	0.044100	0.086600	-0.036372
+2.000388	0.009576	-0.033517	9.774877	0.043700	0.086600	-0.036639
+2.001346	0.014364	-0.019152	9.798818	0.045165	0.089132	-0.038904
+2.002395	-0.011970	0.023940	9.810788	0.047031	0.089265	-0.038371
+2.003388	-0.047881	-0.023940	9.798818	0.049162	0.088332	-0.037571
+2.004393	-0.071821	-0.038305	9.762907	0.048896	0.089931	-0.038637
+2.005391	-0.004788	-0.045487	9.834729	0.043433	0.085801	-0.038504
+2.006391	0.023940	-0.052669	9.849093	0.043034	0.086334	-0.038237
+2.007365	0.052669	-0.067033	9.834729	0.047164	0.085268	-0.034507
+2.008391	0.019152	-0.067033	9.762907	0.048763	0.086867	-0.033974
+2.009359	-0.007182	0.000000	9.755725	0.048363	0.090064	-0.037438
+2.010321	-0.026334	0.016758	9.806000	0.046764	0.089265	-0.038371
+2.011393	0.002394	-0.021546	9.870639	0.046231	0.089798	-0.037438
+2.012391	0.021546	0.014364	9.827546	0.046631	0.086067	-0.035306
+2.013390	0.000000	0.023940	9.774877	0.044100	0.085268	-0.030377
+2.014379	0.028729	-0.021546	9.779666	0.045032	0.088599	-0.031842
+2.015354	0.011970	-0.079003	9.825152	0.046764	0.089132	-0.033841
+2.016326	0.000000	-0.083792	9.777271	0.048496	0.089931	-0.037838
+2.017325	0.050275	0.004788	9.791636	0.045698	0.088599	-0.035972
+2.018391	0.021546	-0.026334	9.779666	0.046364	0.090331	-0.036905
+2.019449	0.007182	0.004788	9.815576	0.044899	0.090997	-0.035706
+2.020453	0.031123	-0.033517	9.861063	0.044499	0.087400	-0.037571
+2.021407	0.050275	-0.033517	9.858669	0.045032	0.087000	-0.037971
+2.022453	-0.052669	-0.064639	9.846699	0.044100	0.086600	-0.034374
+2.023451	-0.021546	-0.014364	9.753331	0.046098	0.087933	-0.035173
+2.024383	0.023940	-0.007182	9.784454	0.049828	0.086467	-0.040103
+2.025354	0.004788	0.000000	9.856275	0.048496	0.086201	-0.041302
+2.026351	0.067033	0.021546	9.841911	0.046364	0.088466	-0.039570
+2.027354	0.045487	-0.009576	9.746149	0.047830	0.090597	-0.034507
+2.028318	0.050275	0.045487	9.786848	0.046498	0.091130	-0.034107
+2.029386	0.004788	0.009576	9.738967	0.047430	0.088599	-0.035440
+2.030388	-0.004788	-0.057457	9.784454	0.048230	0.086734	-0.036106
+2.031356	0.021546	-0.059851	9.765301	0.047830	0.087533	-0.035173
+2.032364	0.100550	-0.023940	9.715026	0.049296	0.087666	-0.034773
+2.033366	0.038305	-0.033517	9.750937	0.047697	0.085268	-0.034507
+2.034405	0.026334	-0.016758	9.794030	0.046631	0.082870	-0.037038
+2.035386	0.028729	-0.045487	9.858669	0.043966	0.083936	-0.034773
+2.036386	-0.026334	-0.004788	9.896974	0.044366	0.087400	-0.034640
+2.037386	-0.059851	0.011970	9.813182	0.045432	0.088998	-0.036639
+2.038390	0.038305	0.035911	9.789242	0.045832	0.091263	-0.037172
+2.039406	0.064639	-0.011970	9.782060	0.047830	0.088865	-0.036905
+2.040409	0.023940	-0.004788	9.822758	0.046764	0.085801	-0.037438
+2.041408	0.009576	-0.019152	9.803606	0.046764	0.088066	-0.039170
+2.042394	0.014364	0.011970	9.782060	0.047164	0.089398	-0.034374
+2.043433	-0.002394	-0.004788	9.808394	0.048496	0.087933	-0.033308
+2.044453	-0.004788	-0.019152	9.801212	0.048496	0.089931	-0.035839
+2.045409	-0.035911	0.000000	9.791636	0.048496	0.088998	-0.035839
+2.046456	0.028729	0.033517	9.779666	0.046098	0.086067	-0.034907
+2.047451	-0.004788	0.016758	9.892186	0.046364	0.086867	-0.035573
+2.048451	0.059851	0.000000	9.825152	0.047297	0.089398	-0.037305
+2.049454	0.011970	-0.004788	9.760513	0.046631	0.089798	-0.037172
+2.050391	0.028729	-0.038305	9.786848	0.045299	0.090331	-0.035573
+2.051445	0.052669	-0.047881	9.772483	0.046364	0.086600	-0.036505
+2.052390	0.016758	-0.014364	9.794030	0.045832	0.085934	-0.036372
+2.053452	0.069427	0.014364	9.738967	0.046098	0.086600	-0.033308
+2.054457	0.026334	0.011970	9.803606	0.047297	0.086867	-0.037438
+2.055454	0.002394	0.000000	9.750937	0.046764	0.087666	-0.039037
+2.056451	-0.023940	0.016758	9.758119	0.044899	0.088199	-0.039836
+2.057453	-0.062245	0.050275	9.839517	0.045965	0.088998	-0.039570
+2.058452	-0.040699	0.021546	9.832334	0.048230	0.088332	-0.037971
+2.059405	-0.047881	-0.047881	9.841911	0.049828	0.087000	-0.038904
+2.060400	-0.016758	-0.083792	9.748543	0.048496	0.087933	-0.038104
+2.061451	0.021546	-0.019152	9.762907	0.046231	0.087666	-0.036106
+2.062454	-0.016758	-0.026334	9.846699	0.048230	0.085934	-0.036905
+2.063452	0.040699	-0.038305	9.896974	0.049695	0.088332	-0.035972
+2.064412	0.062245	-0.064639	9.875427	0.049029	0.088732	-0.035706
+2.065385	-0.011970	-0.016758	9.801212	0.050228	0.087133	-0.034640
+2.066454	-0.021546	0.011970	9.832334	0.048629	0.087000	-0.036505
+2.067450	0.021546	-0.045487	9.863457	0.045698	0.087666	-0.035173
+2.068385	0.002394	-0.019152	9.767695	0.046897	0.087799	-0.035173
+2.069385	0.031123	0.016758	9.789242	0.049962	0.085934	-0.032775
+2.070453	0.055063	0.000000	9.853881	0.048629	0.088732	-0.033841
+2.071391	0.052669	-0.026334	9.832334	0.046098	0.091397	-0.037838
+2.072390	0.043093	0.059851	9.789242	0.043300	0.090331	-0.037438
+2.073390	0.011970	-0.023940	9.715026	0.043300	0.088466	-0.035573
+2.074394	0.014364	0.011970	9.746149	0.047564	0.087133	-0.035706
+2.075455	-0.023940	0.016758	9.789242	0.047297	0.088066	-0.035573
+2.076453	0.038305	0.004788	9.877821	0.048230	0.088599	-0.038237
+2.077453	0.059851	0.000000	9.904156	0.049162	0.089665	-0.038371
+2.078424	0.083792	0.007182	9.839517	0.047164	0.087933	-0.036905
+2.079410	0.067033	0.043093	9.786848	0.046364	0.087933	-0.037305
+2.080445	0.019152	0.000000	9.770089	0.047164	0.089798	-0.036372
+2.081457	0.038305	-0.026334	9.817970	0.047164	0.090730	-0.035706
+2.082455	0.038305	-0.023940	9.791636	0.047430	0.087400	-0.035706
+2.083451	0.011970	-0.023940	9.817970	0.046498	0.087133	-0.037305
+2.084369	-0.050275	0.014364	9.851487	0.043700	0.086734	-0.035040
+2.085391	-0.028729	0.021546	9.822758	0.045165	0.086067	-0.040769
+2.086410	0.028729	0.019152	9.794030	0.047430	0.090597	-0.037971
+2.087455	-0.004788	0.014364	9.817970	0.047031	0.089132	-0.035306
+2.088407	-0.028729	0.004788	9.868245	0.046897	0.088199	-0.035706
+2.089430	-0.045487	-0.023940	9.880215	0.047564	0.087799	-0.036505
+2.090404	-0.023940	-0.043093	9.806000	0.048896	0.091130	-0.036372
+2.091365	0.007182	0.016758	9.849093	0.048763	0.091663	-0.034773
+2.092404	0.040699	0.035911	9.782060	0.047430	0.088599	-0.034640
+2.093451	0.038305	0.002394	9.755725	0.046231	0.087533	-0.037038
+2.094421	-0.014364	-0.026334	9.767695	0.047430	0.087666	-0.035306
+2.095451	0.016758	0.007182	9.803606	0.047963	0.089798	-0.033441
+2.096453	-0.031123	-0.002394	9.789242	0.047031	0.088466	-0.036639
+2.097410	0.004788	-0.067033	9.820364	0.046231	0.087933	-0.037305
+2.098386	-0.014364	-0.019152	9.896974	0.045565	0.086734	-0.034374
+2.099448	-0.047881	0.019152	9.853881	0.045965	0.087266	-0.035440
+2.100451	-0.043093	0.043093	9.729391	0.046498	0.091530	-0.035440
+2.101407	-0.031123	0.050275	9.839517	0.044899	0.088599	-0.037038
+2.102457	0.009576	0.009576	9.832334	0.043167	0.086734	-0.035706
+2.103450	0.000000	0.016758	9.861063	0.046364	0.088066	-0.034107
+2.104452	-0.007182	0.052669	9.820364	0.049296	0.090064	-0.035173
+2.105456	-0.031123	0.023940	9.861063	0.049562	0.089132	-0.031043
+2.106413	0.009576	-0.026334	9.801212	0.048230	0.087133	-0.033974
+2.107421	0.004788	-0.011970	9.784454	0.047963	0.085801	-0.034507
+2.108401	-0.023940	-0.043093	9.834729	0.047031	0.089398	-0.035972
+2.109426	0.009576	-0.014364	9.746149	0.048230	0.087000	-0.038371
+2.110393	0.050275	-0.038305	9.722208	0.048096	0.087000	-0.038237
+2.111411	0.014364	0.031123	9.829940	0.044233	0.088199	-0.034773
+2.112454	-0.067033	0.002394	9.758119	0.041835	0.088466	-0.036905
+2.113454	0.009576	0.016758	9.798818	0.042368	0.088865	-0.036772
+2.114453	0.002394	0.002394	9.794030	0.046231	0.089798	-0.035173
+2.115377	0.007182	-0.019152	9.832334	0.050761	0.090331	-0.036905
+2.116381	0.057457	-0.016758	9.806000	0.051161	0.090331	-0.035573
+2.117445	0.000000	0.004788	9.851487	0.047697	0.091397	-0.033841
+2.118428	0.002394	0.014364	9.841911	0.046498	0.089665	-0.035306
+2.119385	-0.045487	-0.007182	9.875427	0.046231	0.086334	-0.035306
+2.120453	0.011970	-0.009576	9.796424	0.048096	0.085668	-0.034507
+2.121452	0.035911	-0.023940	9.762907	0.047564	0.083936	-0.037571
+2.122455	-0.019152	0.019152	9.863457	0.046498	0.086867	-0.038104
+2.123451	0.021546	0.033517	9.822758	0.046498	0.089265	-0.039836
+2.124403	-0.019152	0.019152	9.765301	0.046098	0.090464	-0.040769
+2.125405	-0.011970	0.059851	9.760513	0.047830	0.090198	-0.038637
+2.126455	0.002394	-0.019152	9.789242	0.045432	0.090331	-0.035839
+2.127451	0.016758	-0.014364	9.743755	0.044233	0.087266	-0.033041
+2.128453	0.033517	0.004788	9.676722	0.046364	0.087133	-0.035306
+2.129452	0.045487	0.019152	9.738967	0.047697	0.086467	-0.036372
+2.130455	0.002394	-0.033517	9.767695	0.045965	0.087933	-0.034107
+2.131452	-0.002394	-0.047881	9.846699	0.046098	0.090331	-0.035972
+2.132451	0.019152	-0.026334	9.810788	0.046498	0.090597	-0.038770
+2.133406	-0.014364	-0.045487	9.772483	0.046498	0.085801	-0.035306
+2.134411	-0.009576	-0.040699	9.743755	0.047564	0.084868	-0.030910
+2.135452	-0.059851	-0.062245	9.683904	0.047963	0.085268	-0.033974
+2.136450	-0.002394	-0.011970	9.767695	0.047297	0.085401	-0.037571
+2.137452	0.011970	0.028729	9.798818	0.047564	0.085135	-0.039436
+2.138455	0.004788	0.026334	9.741361	0.047430	0.085268	-0.037038
+2.139451	0.011970	0.009576	9.870639	0.044899	0.087133	-0.035173
+2.140407	-0.014364	-0.028729	9.868245	0.043300	0.086334	-0.036372
+2.141390	-0.014364	0.014364	9.858669	0.045965	0.085135	-0.035972
+2.142386	-0.057457	0.045487	9.815576	0.049029	0.087799	-0.035706
+2.143393	0.009576	-0.033517	9.753331	0.049429	0.090198	-0.035573
+2.144451	0.011970	-0.047881	9.779666	0.045965	0.089531	-0.036639
+2.145453	-0.016758	-0.076609	9.839517	0.043833	0.085401	-0.038904
+2.146450	-0.021546	-0.045487	9.786848	0.049429	0.084335	-0.038104
+2.147449	0.047881	-0.004788	9.760513	0.048629	0.085401	-0.037971
+2.148450	0.050275	-0.002394	9.758119	0.045032	0.085268	-0.035573
+2.149450	0.026334	-0.064639	9.777271	0.047297	0.083802	-0.034240
+2.150406	0.028729	-0.074215	9.762907	0.049429	0.084868	-0.033841
+2.151405	0.031123	-0.031123	9.801212	0.048496	0.087000	-0.033974
+2.152406	0.052669	-0.014364	9.849093	0.048629	0.090997	-0.034374
+2.153450	0.050275	0.004788	9.777271	0.048496	0.089798	-0.034640
+2.154408	-0.026334	0.000000	9.798818	0.048496	0.087666	-0.033308
+2.155451	0.043093	-0.043093	9.746149	0.047031	0.089665	-0.033175
+2.156398	0.011970	0.019152	9.755725	0.046231	0.089398	-0.034374
+2.157451	-0.038305	0.004788	9.753331	0.044366	0.086867	-0.037571
+2.158454	0.014364	0.026334	9.801212	0.045299	0.087133	-0.038371
+2.159408	-0.031123	0.035911	9.861063	0.047031	0.089798	-0.037038
+2.160409	-0.050275	-0.009576	9.856275	0.046364	0.090730	-0.038371
+2.161452	-0.011970	-0.059851	9.863457	0.046764	0.088998	-0.037438
+2.162455	-0.040699	-0.026334	9.784454	0.047031	0.089265	-0.035972
+2.163446	-0.057457	-0.026334	9.748543	0.045032	0.086067	-0.036372
+2.164445	-0.064639	0.016758	9.815576	0.046897	0.086334	-0.034107
+2.165344	-0.059851	0.007182	9.770089	0.045965	0.085668	-0.034107
+2.166423	-0.045487	-0.028729	9.786848	0.045565	0.085268	-0.039170
+2.167450	0.016758	-0.026334	9.784454	0.047031	0.087933	-0.037438
+2.168402	0.028729	-0.045487	9.837123	0.045698	0.089132	-0.037305
+2.169402	0.050275	-0.047881	9.820364	0.046364	0.088732	-0.035839
+2.170445	0.052669	0.009576	9.841911	0.046364	0.087133	-0.033175
+2.171450	0.002394	-0.031123	9.712632	0.046764	0.087133	-0.033175
+2.172449	-0.023940	0.002394	9.693480	0.047164	0.090064	-0.034640
+2.173451	-0.026334	0.021546	9.774877	0.047164	0.090864	-0.035573
+2.174454	-0.040699	-0.019152	9.794030	0.047297	0.088199	-0.037305
+2.175404	0.000000	0.000000	9.782060	0.048496	0.087666	-0.040369
+2.176377	0.026334	0.002394	9.808394	0.049429	0.087400	-0.037038
+2.177380	0.028729	-0.007182	9.758119	0.049562	0.086600	-0.037438
+2.178383	0.055063	-0.069427	9.786848	0.050361	0.089931	-0.034240
+2.179405	0.033517	-0.002394	9.832334	0.048896	0.090464	-0.033041
+2.180449	0.021546	-0.026334	9.772483	0.046364	0.088998	-0.035440
+2.181451	-0.002394	0.052669	9.849093	0.047031	0.088466	-0.038237
+2.182454	0.059851	0.011970	9.806000	0.048496	0.086334	-0.039303
+2.183406	0.050275	0.023940	9.803606	0.047564	0.086201	-0.034640
+2.184407	0.016758	0.000000	9.832334	0.045299	0.088066	-0.034907
+2.185409	-0.004788	-0.067033	9.786848	0.044233	0.088199	-0.036106
+2.186451	0.014364	0.011970	9.851487	0.046498	0.086734	-0.036772
+2.187403	0.038305	-0.007182	9.803606	0.048763	0.082870	-0.040369
+2.188395	0.019152	-0.009576	9.748543	0.047963	0.085268	-0.038237
+2.189453	0.028729	-0.035911	9.798818	0.045432	0.087666	-0.037704
+2.190454	0.000000	0.019152	9.870639	0.046364	0.086734	-0.034773
+2.191452	-0.002394	-0.040699	9.772483	0.047830	0.087000	-0.034907
+2.192457	-0.031123	-0.043093	9.875427	0.048363	0.087533	-0.035573
+2.193452	0.011970	0.047881	9.837123	0.050095	0.087000	-0.034907
+2.194453	0.011970	0.052669	9.820364	0.049562	0.086734	-0.035839
+2.195455	-0.038305	-0.007182	9.889792	0.047963	0.086334	-0.035972
+2.196405	-0.002394	-0.031123	9.798818	0.048230	0.085401	-0.038371
+2.197449	0.028729	-0.019152	9.841911	0.047830	0.085401	-0.036505
+2.198457	0.038305	-0.033517	9.928096	0.046631	0.086334	-0.032508
+2.199451	-0.031123	-0.045487	9.849093	0.047430	0.088066	-0.031443
+2.200454	-0.004788	-0.009576	9.880215	0.047031	0.088998	-0.035706
+2.201421	0.033517	0.021546	9.806000	0.047963	0.087266	-0.035573
+2.202452	0.059851	-0.031123	9.841911	0.048096	0.087933	-0.037038
+2.203395	0.026334	-0.035911	9.863457	0.044632	0.086867	-0.035972
+2.204379	0.007182	-0.011970	9.782060	0.045165	0.085534	-0.034907
+2.205407	0.000000	0.016758	9.808394	0.045165	0.087000	-0.035706
+2.206448	-0.023940	0.023940	9.762907	0.047297	0.087000	-0.036905
+2.207452	0.011970	0.011970	9.796424	0.046764	0.086067	-0.037438
+2.208367	-0.007182	-0.019152	9.808394	0.047430	0.088998	-0.037838
+2.209454	0.002394	-0.045487	9.791636	0.047963	0.088732	-0.035706
+2.210411	0.028729	-0.040699	9.882609	0.046631	0.088865	-0.036505
+2.211450	0.000000	-0.043093	9.786848	0.048363	0.088998	-0.035839
+2.212451	-0.014364	-0.052669	9.765301	0.047697	0.090064	-0.036372
+2.213450	0.031123	0.014364	9.712632	0.046498	0.087400	-0.039436
+2.214452	0.009576	-0.004788	9.765301	0.046498	0.087266	-0.038770
+2.215393	-0.038305	-0.050275	9.760513	0.046631	0.087799	-0.039436
+2.216383	-0.035911	-0.057457	9.762907	0.046364	0.088599	-0.036639
+2.217382	0.016758	0.000000	9.784454	0.047963	0.088332	-0.033974
+2.218376	0.011970	0.050275	9.750937	0.047697	0.086734	-0.034773
+2.219451	0.016758	0.040699	9.820364	0.045965	0.087266	-0.038237
+2.220389	-0.023940	0.031123	9.844305	0.047830	0.089798	-0.039037
+2.221450	0.000000	0.004788	9.837123	0.047430	0.089931	-0.032508
+2.222450	0.057457	-0.033517	9.777271	0.045698	0.090064	-0.036239
+2.223444	0.009576	-0.014364	9.837123	0.045965	0.090597	-0.037571
+2.224398	-0.014364	-0.014364	9.880215	0.045965	0.088732	-0.038104
+2.225378	0.023940	-0.019152	9.832334	0.046098	0.087933	-0.037971
+2.226358	0.038305	-0.031123	9.832334	0.048896	0.088199	-0.037305
+2.227359	0.069427	-0.043093	9.832334	0.048896	0.088732	-0.034240
+2.228360	0.047881	-0.016758	9.810788	0.047564	0.086067	-0.034907
+2.229356	0.028729	0.038305	9.777271	0.046364	0.089265	-0.035573
+2.230362	0.016758	0.021546	9.798818	0.046098	0.089132	-0.037038
+2.231360	0.045487	-0.007182	9.877821	0.046098	0.085801	-0.037438
+2.232361	-0.011970	-0.002394	9.829940	0.047164	0.085668	-0.034374
+2.233365	0.011970	0.014364	9.786848	0.047164	0.087000	-0.034374
+2.234315	0.081397	0.000000	9.815576	0.047031	0.088732	-0.036239
+2.235316	0.079003	0.009576	9.875427	0.045965	0.090864	-0.037704
+2.236356	0.026334	-0.009576	9.796424	0.044632	0.087799	-0.038237
+2.237390	0.000000	0.026334	9.786848	0.047031	0.086201	-0.036905
+2.238391	-0.026334	0.011970	9.825152	0.049429	0.087933	-0.034240
+2.239390	-0.014364	0.059851	9.808394	0.048629	0.090597	-0.032775
+2.240391	0.038305	0.016758	9.777271	0.046231	0.088998	-0.032242
+2.241395	-0.002394	-0.031123	9.731785	0.046498	0.087400	-0.036505
+2.242393	0.009576	-0.035911	9.777271	0.045832	0.086600	-0.036639
+2.243391	0.033517	-0.011970	9.801212	0.048496	0.086867	-0.034640
+2.244390	0.031123	-0.074215	9.885003	0.048496	0.084602	-0.036372
+2.245385	-0.014364	-0.038305	9.798818	0.047297	0.085135	-0.034773
+2.246404	-0.026334	-0.011970	9.762907	0.047963	0.087666	-0.035706
+2.247371	0.004788	-0.023940	9.841911	0.047830	0.086334	-0.035306
+2.248395	0.021546	-0.009576	9.877821	0.046897	0.088732	-0.033041
+2.249336	0.038305	0.040699	9.789242	0.047564	0.088199	-0.037172
+2.250394	0.069427	0.057457	9.841911	0.049162	0.084868	-0.036772
+2.251389	0.019152	-0.028729	9.853881	0.048496	0.086467	-0.037571
+2.252392	0.004788	-0.033517	9.777271	0.045032	0.086867	-0.037838
+2.253392	0.000000	-0.050275	9.753331	0.042900	0.089531	-0.039969
+2.254330	0.011970	-0.014364	9.834729	0.046231	0.087000	-0.040769
+2.255390	-0.021546	-0.016758	9.849093	0.046897	0.085401	-0.040636
+2.256394	-0.009576	0.007182	9.901762	0.048096	0.082337	-0.039436
+2.257361	0.009576	0.021546	9.820364	0.048896	0.084202	-0.038371
+2.258391	0.055063	0.016758	9.801212	0.047963	0.085668	-0.035839
+2.259392	-0.023940	-0.014364	9.774877	0.047031	0.088066	-0.035306
+2.260330	0.043093	0.016758	9.774877	0.045565	0.086600	-0.034240
+2.261392	0.028729	-0.011970	9.784454	0.046231	0.087799	-0.035972
+2.262391	-0.002394	-0.038305	9.762907	0.046231	0.089665	-0.036505
+2.263355	-0.019152	0.007182	9.825152	0.043966	0.089265	-0.037038
+2.264324	-0.009576	-0.062245	9.834729	0.045565	0.087933	-0.038371
+2.265389	0.014364	-0.052669	9.851487	0.048496	0.087133	-0.038904
+2.266390	-0.045487	-0.052669	9.782060	0.050495	0.088199	-0.033841
+2.267384	0.009576	-0.059851	9.813182	0.050228	0.087133	-0.032508
+2.268344	0.009576	-0.019152	9.729391	0.049562	0.084335	-0.039170
+2.269304	0.050275	0.040699	9.839517	0.045698	0.086201	-0.040502
+2.270357	0.021546	-0.002394	9.861063	0.045032	0.087000	-0.037038
+2.271354	0.043093	0.033517	9.784454	0.046631	0.088199	-0.036239
+2.272355	-0.045487	-0.002394	9.729391	0.047963	0.087000	-0.034240
+2.273385	-0.057457	-0.019152	9.710238	0.046631	0.084602	-0.035839
+2.274379	-0.009576	-0.057457	9.762907	0.044366	0.083536	-0.037838
+2.275381	0.031123	-0.040699	9.839517	0.045165	0.085268	-0.036239
+2.276377	0.021546	-0.007182	9.887397	0.044233	0.086734	-0.033974
+2.277380	0.028729	-0.019152	9.832334	0.044899	0.088466	-0.032375
+2.278380	0.062245	-0.055063	9.817970	0.047963	0.085801	-0.032109
+2.279379	0.002394	0.007182	9.755725	0.051827	0.085668	-0.035173
+2.280377	-0.040699	-0.033517	9.853881	0.048896	0.087533	-0.036372
+2.281381	-0.026334	-0.062245	9.796424	0.044366	0.089132	-0.035440
+2.282315	-0.004788	-0.047881	9.791636	0.043966	0.087666	-0.032375
+2.283304	0.045487	-0.011970	9.806000	0.047564	0.088599	-0.034240
+2.284311	0.038305	0.009576	9.813182	0.048896	0.088865	-0.034907
+2.285312	0.035911	0.062245	9.743755	0.050628	0.086067	-0.035173
+2.286312	0.043093	0.040699	9.750937	0.047697	0.087400	-0.034240
+2.287311	0.090974	0.007182	9.777271	0.047297	0.087533	-0.035972
+2.288311	0.064639	-0.026334	9.777271	0.045165	0.087533	-0.036505
+2.289312	0.002394	-0.033517	9.839517	0.046631	0.088466	-0.037038
+2.290311	0.002394	-0.055063	9.899368	0.049429	0.088732	-0.036772
+2.291333	0.033517	-0.040699	9.810788	0.048096	0.086734	-0.035839
+2.292328	-0.009576	0.002394	9.837123	0.048363	0.087133	-0.033841
+2.293347	0.004788	0.028729	9.894580	0.049562	0.086867	-0.035573
+2.294377	0.043093	-0.028729	9.796424	0.045965	0.085002	-0.037305
+2.295390	0.093368	-0.055063	9.772483	0.043700	0.084735	-0.037172
+2.296374	0.059851	-0.031123	9.853881	0.047430	0.088466	-0.037571
+2.297384	0.079003	-0.071821	9.820364	0.048629	0.091263	-0.040502
+2.298391	-0.004788	-0.031123	9.827546	0.049029	0.091263	-0.038504
+2.299343	0.000000	-0.064639	9.832334	0.047031	0.089798	-0.032775
+2.300388	0.000000	-0.067033	9.834729	0.047430	0.088199	-0.033841
+2.301370	-0.009576	-0.045487	9.827546	0.047564	0.087400	-0.035972
+2.302384	-0.007182	0.009576	9.837123	0.046364	0.087799	-0.038504
+2.303388	-0.031123	0.009576	9.822758	0.044100	0.089665	-0.036239
+2.304332	-0.011970	0.040699	9.810788	0.046631	0.088199	-0.034507
+2.305388	0.009576	0.000000	9.908944	0.047031	0.086734	-0.035706
+2.306392	0.052669	-0.014364	9.772483	0.044766	0.087799	-0.036239
+2.307391	0.059851	-0.019152	9.770089	0.045698	0.087533	-0.037571
+2.308390	0.086186	-0.004788	9.803606	0.046364	0.089265	-0.034107
+2.309388	0.021546	0.009576	9.851487	0.047963	0.089398	-0.034107
+2.310391	0.014364	-0.011970	9.789242	0.047697	0.088332	-0.036639
+2.311388	0.043093	-0.002394	9.846699	0.045565	0.088332	-0.039703
+2.312391	0.131672	0.021546	9.820364	0.044499	0.089665	-0.039969
+2.313392	0.002394	-0.004788	9.841911	0.044632	0.092462	-0.037571
+2.314374	-0.031123	-0.026334	9.829940	0.044899	0.089798	-0.036639
+2.315350	0.011970	0.009576	9.834729	0.045299	0.087000	-0.035972
+2.316340	-0.026334	-0.016758	9.794030	0.046231	0.087266	-0.034907
+2.317389	-0.014364	0.016758	9.789242	0.045698	0.088599	-0.034773
+2.318315	0.004788	0.016758	9.746149	0.047564	0.088332	-0.035839
+2.319344	0.021546	0.023940	9.784454	0.047963	0.089398	-0.034773
+2.320334	0.004788	0.002394	9.846699	0.048096	0.090864	-0.032775
+2.321334	0.000000	0.002394	9.791636	0.046631	0.088199	-0.036372
+2.322335	0.004788	-0.019152	9.770089	0.047297	0.086467	-0.035573
+2.323383	-0.023940	-0.021546	9.875427	0.048496	0.089265	-0.034374
+2.324353	-0.004788	0.002394	9.770089	0.049828	0.090730	-0.036372
+2.325349	0.000000	0.035911	9.767695	0.051560	0.088998	-0.039037
+2.326390	0.009576	0.040699	9.743755	0.048763	0.087133	-0.040636
+2.327383	0.011970	0.028729	9.774877	0.046897	0.087266	-0.040103
+2.328389	0.019152	-0.064639	9.803606	0.046897	0.085668	-0.037038
+2.329391	0.009576	0.002394	9.798818	0.046764	0.086734	-0.036505
+2.330391	-0.019152	-0.031123	9.822758	0.048096	0.089665	-0.032242
+2.331390	-0.057457	0.000000	9.798818	0.049695	0.089398	-0.030377
+2.332390	-0.071821	0.014364	9.715026	0.048896	0.087000	-0.035173
+2.333388	-0.055063	0.033517	9.738967	0.049029	0.086600	-0.035839
+2.334331	-0.100550	-0.019152	9.719814	0.046231	0.089398	-0.036772
+2.335369	-0.002394	0.000000	9.715026	0.045432	0.090064	-0.036239
+2.336324	-0.023940	0.009576	9.803606	0.048230	0.089931	-0.032508
+2.337325	-0.014364	0.028729	9.817970	0.048230	0.088732	-0.036639
+2.338346	0.000000	0.009576	9.880215	0.046364	0.086467	-0.038770
+2.339342	0.002394	0.007182	9.806000	0.046098	0.086201	-0.038770
+2.340388	0.007182	-0.016758	9.770089	0.044899	0.085668	-0.038904
+2.341388	-0.011970	-0.007182	9.784454	0.047564	0.086067	-0.039303
+2.342371	-0.011970	-0.011970	9.791636	0.048896	0.087400	-0.036905
+2.343339	0.019152	-0.002394	9.834729	0.048096	0.089798	-0.034240
+2.344375	-0.009576	0.050275	9.794030	0.047430	0.088199	-0.034107
+2.345366	0.011970	0.009576	9.772483	0.046231	0.085135	-0.037438
+2.346323	0.023940	0.000000	9.794030	0.044366	0.085534	-0.040636
+2.347410	0.052669	-0.043093	9.741361	0.044100	0.087666	-0.038904
+2.348341	0.016758	-0.081397	9.743755	0.045698	0.090864	-0.038104
+2.349339	0.023940	-0.016758	9.782060	0.047430	0.090597	-0.037838
+2.350313	0.016758	-0.009576	9.777271	0.046897	0.090331	-0.034240
+2.351386	0.000000	0.016758	9.750937	0.047564	0.088332	-0.034907
+2.352388	0.035911	0.026334	9.827546	0.047430	0.086867	-0.037571
+2.353393	0.004788	-0.026334	9.791636	0.048230	0.087533	-0.039703
+2.354334	-0.014364	-0.004788	9.789242	0.046897	0.086734	-0.038770
+2.355390	-0.033517	0.011970	9.810788	0.047031	0.085002	-0.036239
+2.356369	-0.011970	0.007182	9.815576	0.047830	0.086734	-0.036505
+2.357385	0.014364	0.026334	9.803606	0.045965	0.089531	-0.034773
+2.358386	0.033517	-0.043093	9.767695	0.043300	0.088066	-0.035173
+2.359388	-0.002394	0.023940	9.719814	0.045965	0.087666	-0.037038
+2.360384	0.009576	0.028729	9.772483	0.047830	0.088998	-0.038237
+2.361395	0.038305	0.045487	9.796424	0.048763	0.088865	-0.037038
+2.362391	-0.062245	0.014364	9.853881	0.048230	0.087933	-0.036372
+2.363389	-0.067033	-0.009576	9.851487	0.044632	0.086734	-0.034240
+2.364388	-0.028729	0.067033	9.762907	0.045032	0.089265	-0.036106
+2.365323	-0.019152	0.031123	9.765301	0.046364	0.088199	-0.037305
+2.366337	0.047881	0.002394	9.808394	0.046231	0.087133	-0.035573
+2.367325	0.038305	-0.064639	9.772483	0.047031	0.087133	-0.034240
+2.368404	-0.002394	-0.002394	9.858669	0.047697	0.087799	-0.033041
+2.369394	-0.028729	-0.021546	9.844305	0.046098	0.087933	-0.033841
+2.370343	0.031123	-0.009576	9.870639	0.046631	0.084469	-0.037438
+2.371389	0.045487	0.009576	9.817970	0.045432	0.084602	-0.036372
+2.372342	0.011970	-0.007182	9.834729	0.045565	0.086467	-0.036239
+2.373389	-0.007182	-0.007182	9.853881	0.045432	0.087266	-0.037438
+2.374389	0.009576	-0.004788	9.810788	0.048096	0.087400	-0.038770
+2.375325	0.035911	0.023940	9.765301	0.047430	0.087000	-0.039836
+2.376339	0.038305	-0.019152	9.851487	0.046498	0.086201	-0.037704
+2.377304	0.026334	-0.059851	9.858669	0.047031	0.087000	-0.034374
+2.378316	0.026334	0.021546	9.853881	0.046897	0.090464	-0.037305
+2.379324	0.040699	0.043093	9.760513	0.046897	0.089665	-0.036505
+2.380379	0.033517	-0.043093	9.782060	0.048096	0.087000	-0.035173
+2.381344	0.023940	0.007182	9.765301	0.047830	0.086734	-0.035706
+2.382384	-0.009576	-0.007182	9.736573	0.046764	0.086867	-0.035573
+2.383379	-0.026334	-0.043093	9.856275	0.046364	0.087666	-0.036106
+2.384378	0.038305	-0.002394	9.841911	0.045832	0.088199	-0.037305
+2.385391	0.069427	-0.016758	9.887397	0.045965	0.088732	-0.035573
+2.386450	0.004788	0.004788	9.849093	0.044499	0.088332	-0.035706
+2.387407	0.011970	-0.019152	9.767695	0.047031	0.086600	-0.036106
+2.388404	-0.014364	0.014364	9.901762	0.050361	0.086600	-0.037438
+2.389382	-0.021546	0.016758	9.837123	0.048230	0.089665	-0.038637
+2.390338	-0.009576	-0.031123	9.758119	0.044766	0.088865	-0.036905
+2.391329	0.014364	-0.031123	9.760513	0.044899	0.089798	-0.037571
+2.392354	0.016758	0.009576	9.777271	0.047430	0.090730	-0.038770
+2.393413	0.009576	-0.002394	9.834729	0.048096	0.088199	-0.038371
+2.394365	0.026334	-0.004788	9.832334	0.048496	0.087000	-0.037038
+2.395405	0.023940	0.026334	9.827546	0.048096	0.087400	-0.031842
+2.396406	0.004788	-0.004788	9.767695	0.046231	0.089265	-0.033974
+2.397407	0.035911	-0.052669	9.851487	0.047963	0.090064	-0.036505
+2.398406	0.045487	-0.028729	9.916126	0.048763	0.089132	-0.039037
+2.399377	-0.002394	-0.019152	9.882609	0.046498	0.090331	-0.037438
+2.400338	-0.023940	0.002394	9.760513	0.043966	0.089398	-0.037838
+2.401351	0.026334	-0.040699	9.765301	0.043700	0.089398	-0.037704
+2.402358	0.016758	-0.028729	9.827546	0.046231	0.088998	-0.035440
+2.403339	0.059851	-0.033517	9.827546	0.048096	0.087533	-0.031309
+2.404356	0.035911	0.050275	9.789242	0.047963	0.088066	-0.036505
+2.405336	0.033517	0.035911	9.827546	0.045299	0.084469	-0.037704
+2.406353	0.016758	0.007182	9.906550	0.045832	0.085268	-0.037971
+2.407358	0.011970	-0.016758	9.782060	0.046764	0.088599	-0.034773
+2.408376	-0.040699	-0.021546	9.806000	0.049429	0.087133	-0.035972
+2.409342	-0.052669	0.038305	9.817970	0.051028	0.088199	-0.032375
+2.410376	0.007182	0.009576	9.911338	0.048363	0.088066	-0.033308
+2.411376	0.009576	-0.028729	9.885003	0.046897	0.088066	-0.035573
+2.412429	0.016758	-0.007182	9.784454	0.045698	0.084868	-0.038904
+2.413440	0.040699	-0.014364	9.717420	0.043966	0.084069	-0.038504
+2.414383	-0.014364	0.023940	9.779666	0.045698	0.084735	-0.038371
+2.415369	-0.016758	-0.007182	9.825152	0.047830	0.087000	-0.036106
+2.416367	-0.021546	-0.035911	9.765301	0.049029	0.089798	-0.037438
+2.417440	0.021546	-0.067033	9.798818	0.046098	0.089931	-0.037971
+2.418404	-0.009576	-0.035911	9.767695	0.046764	0.086600	-0.038770
+2.419438	0.026334	-0.004788	9.741361	0.048230	0.084868	-0.039969
+2.420408	0.117308	-0.019152	9.813182	0.047697	0.086067	-0.041168
+2.421393	0.028729	0.014364	9.786848	0.048096	0.086734	-0.036239
+2.422396	-0.035911	-0.014364	9.798818	0.048496	0.089265	-0.033974
+2.423339	-0.007182	0.004788	9.832334	0.048230	0.089931	-0.035573
+2.424336	-0.011970	-0.014364	9.815576	0.047564	0.088199	-0.037971
+2.425325	-0.035911	-0.016758	9.827546	0.044100	0.087133	-0.037172
+2.426316	-0.007182	-0.059851	9.798818	0.045565	0.085401	-0.038104
+2.427320	0.009576	-0.076609	9.794030	0.046498	0.085534	-0.038104
+2.428310	0.000000	-0.076609	9.801212	0.048763	0.085934	-0.040769
+2.429327	-0.026334	-0.045487	9.853881	0.047963	0.088066	-0.039969
+2.430329	-0.038305	0.057457	9.822758	0.047297	0.088865	-0.034773
+2.431347	0.000000	0.052669	9.822758	0.047830	0.086867	-0.035706
+2.432345	-0.031123	0.031123	9.767695	0.049695	0.087133	-0.037571
+2.433369	-0.026334	-0.052669	9.779666	0.046631	0.086201	-0.037571
+2.434338	-0.019152	-0.021546	9.846699	0.044766	0.087666	-0.035440
+2.435340	0.038305	-0.031123	9.801212	0.048363	0.088332	-0.034507
+2.436359	0.062245	-0.004788	9.767695	0.049695	0.087666	-0.033041
+2.437418	0.033517	0.028729	9.746149	0.049029	0.084735	-0.034907
+2.438422	0.031123	-0.033517	9.791636	0.046897	0.088066	-0.035706
+2.439418	0.011970	-0.009576	9.786848	0.048763	0.089798	-0.037038
+2.440415	0.004788	-0.004788	9.794030	0.050361	0.087266	-0.037305
+2.441423	0.016758	-0.093368	9.722208	0.047297	0.087000	-0.037438
+2.442363	0.033517	-0.079003	9.796424	0.045565	0.087799	-0.036372
+2.443361	0.031123	-0.045487	9.837123	0.045299	0.086067	-0.036106
+2.444402	-0.011970	-0.031123	9.779666	0.045565	0.088066	-0.035440
+2.445418	0.026334	-0.055063	9.767695	0.048096	0.090064	-0.034640
+2.446423	0.052669	-0.057457	9.851487	0.047164	0.086467	-0.036106
+2.447418	0.019152	0.031123	9.789242	0.045165	0.084868	-0.035173
+2.448418	0.021546	-0.019152	9.813182	0.045832	0.087400	-0.035306
+2.449418	0.021546	0.004788	9.839517	0.048230	0.088599	-0.033441
+2.450420	0.079003	-0.016758	9.849093	0.049162	0.089798	-0.033308
+2.451345	0.007182	0.000000	9.851487	0.048763	0.088599	-0.035440
+2.452377	0.004788	0.014364	9.810788	0.047031	0.087799	-0.035839
+2.453415	-0.021546	-0.014364	9.784454	0.044366	0.090064	-0.036505
+2.454422	-0.009576	0.004788	9.770089	0.044766	0.088066	-0.037971
+2.455419	0.023940	0.009576	9.782060	0.047697	0.086734	-0.036772
+2.456420	0.052669	-0.019152	9.798818	0.047564	0.089931	-0.033441
+2.457422	0.052669	-0.004788	9.767695	0.048763	0.089931	-0.034240
+2.458419	0.028729	-0.007182	9.707844	0.047697	0.087533	-0.039703
+2.459419	-0.002394	-0.028729	9.782060	0.046631	0.088066	-0.040769
+2.460376	0.035911	0.002394	9.892186	0.046498	0.089132	-0.036505
+2.461365	0.055063	0.000000	9.791636	0.045832	0.089798	-0.036905
+2.462420	-0.016758	-0.057457	9.758119	0.047697	0.089132	-0.038770
+2.463419	0.011970	-0.038305	9.806000	0.046231	0.087400	-0.039037
+2.464363	0.019152	0.014364	9.928096	0.045965	0.090064	-0.039836
+2.465419	0.035911	-0.040699	9.844305	0.046498	0.089931	-0.038104
+2.466364	0.038305	-0.004788	9.858669	0.048496	0.084469	-0.038371
+2.467358	0.086186	0.011970	9.748543	0.048230	0.084069	-0.039436
+2.468357	0.067033	0.028729	9.791636	0.047031	0.088199	-0.036905
+2.469418	0.038305	0.055063	9.736573	0.046364	0.088066	-0.036505
+2.470387	0.028729	0.019152	9.808394	0.045965	0.085934	-0.037438
+2.471395	0.014364	-0.031123	9.750937	0.044499	0.083669	-0.037838
+2.472418	0.031123	-0.016758	9.815576	0.046098	0.085801	-0.036106
+2.473362	-0.004788	-0.004788	9.808394	0.048230	0.085934	-0.034374
+2.474403	-0.002394	-0.002394	9.736573	0.049029	0.085934	-0.033175
+2.475414	0.047881	-0.045487	9.705450	0.043966	0.088599	-0.036505
+2.476419	0.033517	-0.014364	9.784454	0.044899	0.089398	-0.035573
+2.477419	0.009576	0.016758	9.834729	0.046897	0.088466	-0.035706
+2.478370	0.033517	-0.019152	9.851487	0.046498	0.084735	-0.038371
+2.479415	0.050275	-0.067033	9.789242	0.047697	0.084069	-0.038371
+2.480392	0.055063	0.000000	9.791636	0.049695	0.088066	-0.034374
+2.481358	0.038305	-0.023940	9.827546	0.045299	0.087933	-0.035972
+2.482424	0.055063	-0.043093	9.770089	0.045165	0.090730	-0.035706
+2.483420	0.057457	0.019152	9.772483	0.045565	0.089398	-0.036372
+2.484419	0.007182	-0.016758	9.767695	0.045698	0.085668	-0.037038
+2.485419	-0.057457	0.011970	9.710238	0.044366	0.083536	-0.038637
+2.486401	-0.028729	0.019152	9.760513	0.044632	0.085534	-0.037305
+2.487412	-0.021546	0.009576	9.846699	0.045565	0.089265	-0.036639
+2.488418	0.026334	0.023940	9.777271	0.047297	0.091663	-0.036772
+2.489381	0.038305	0.021546	9.777271	0.047164	0.090864	-0.033841
+2.490371	0.028729	-0.016758	9.738967	0.047031	0.087133	-0.034507
+2.491359	-0.028729	0.026334	9.798818	0.045565	0.086067	-0.035706
+2.492359	-0.021546	0.011970	9.839517	0.047564	0.086334	-0.035972
+2.493358	0.062245	0.011970	9.877821	0.046098	0.089531	-0.038637
+2.494358	0.021546	-0.074215	9.789242	0.045698	0.089798	-0.037971
+2.495352	-0.004788	-0.052669	9.734179	0.047697	0.088199	-0.037172
+2.496357	0.014364	-0.033517	9.801212	0.048230	0.087133	-0.037838
+2.497419	0.045487	-0.023940	9.887397	0.048496	0.086467	-0.039436
+2.498416	0.014364	-0.033517	9.841911	0.046897	0.085268	-0.037172
+2.499381	-0.002394	-0.047881	9.861063	0.047031	0.086600	-0.034907
+2.500406	-0.009576	-0.011970	9.858669	0.046498	0.086867	-0.035573
+2.501421	0.016758	0.014364	9.777271	0.046098	0.083403	-0.035306
+2.502418	-0.021546	-0.023940	9.822758	0.046498	0.085002	-0.033841
+2.503418	-0.007182	-0.043093	9.798818	0.046897	0.088199	-0.036505
+2.504362	0.019152	-0.002394	9.808394	0.049029	0.088199	-0.037838
+2.505414	0.014364	-0.007182	9.798818	0.047963	0.090198	-0.040103
+2.506420	0.052669	-0.028729	9.887397	0.045565	0.089132	-0.037172
+2.507408	0.059851	-0.004788	9.803606	0.045565	0.088332	-0.035573
+2.508348	0.031123	-0.023940	9.772483	0.049029	0.087933	-0.036372
+2.509380	-0.019152	0.026334	9.806000	0.049296	0.088066	-0.035040
+2.510363	0.033517	-0.043093	9.777271	0.045832	0.086201	-0.035306
+2.511417	0.023940	-0.062245	9.753331	0.047963	0.086734	-0.037704
+2.512417	-0.021546	0.031123	9.774877	0.046764	0.087666	-0.035306
+2.513420	0.002394	-0.021546	9.798818	0.046498	0.087000	-0.034107
+2.514421	-0.019152	0.004788	9.832334	0.046498	0.085002	-0.034107
+2.515419	0.007182	-0.009576	9.825152	0.047697	0.085002	-0.036372
+2.516339	0.055063	-0.023940	9.851487	0.046231	0.087133	-0.040636
+2.517391	0.014364	-0.023940	9.827546	0.045432	0.087533	-0.042634
+2.518377	-0.007182	-0.047881	9.784454	0.045165	0.086201	-0.040369
+2.519426	0.004788	-0.047881	9.813182	0.045965	0.085801	-0.038104
+2.520451	0.004788	-0.047881	9.741361	0.045965	0.086334	-0.038770
+2.521449	-0.035911	-0.059851	9.789242	0.046764	0.086201	-0.037305
+2.522446	-0.002394	-0.019152	9.734179	0.047564	0.088332	-0.037172
+2.523444	0.038305	-0.016758	9.839517	0.046098	0.088732	-0.034907
+2.524399	0.000000	-0.004788	9.846699	0.048496	0.088865	-0.038637
+2.525442	-0.050275	-0.002394	9.808394	0.048629	0.090597	-0.039836
+2.526363	0.000000	-0.011970	9.911338	0.044899	0.091930	-0.038637
+2.527382	0.009576	0.038305	9.746149	0.046897	0.088199	-0.040236
+2.528444	0.067033	0.007182	9.827546	0.049162	0.086467	-0.038104
+2.529386	0.016758	-0.016758	9.772483	0.048763	0.085668	-0.036372
+2.530389	-0.031123	0.014364	9.734179	0.048096	0.087533	-0.035972
+2.531406	-0.014364	0.011970	9.813182	0.048896	0.087000	-0.038371
+2.532372	0.000000	-0.031123	9.863457	0.050228	0.087133	-0.037172
+2.533376	0.007182	-0.031123	9.779666	0.047430	0.087133	-0.034507
+2.534447	-0.004788	-0.038305	9.822758	0.046231	0.088599	-0.035573
+2.535380	-0.004788	-0.033517	9.873033	0.045698	0.087400	-0.036905
+2.536377	0.004788	0.016758	9.856275	0.047031	0.091130	-0.035573
+2.537447	0.004788	-0.011970	9.837123	0.049562	0.090730	-0.039570
+2.538376	0.021546	-0.009576	9.755725	0.049695	0.088332	-0.038371
+2.539426	-0.011970	0.033517	9.767695	0.046231	0.087666	-0.034773
+2.540457	-0.033517	-0.009576	9.796424	0.046764	0.086600	-0.033175
+2.541376	-0.011970	-0.055063	9.896974	0.048896	0.088599	-0.033041
+2.542449	0.007182	0.009576	9.786848	0.049162	0.088865	-0.037038
+2.543401	-0.009576	-0.011970	9.806000	0.045165	0.088732	-0.038770
+2.544404	0.021546	-0.062245	9.806000	0.046631	0.089665	-0.040769
+2.545447	0.055063	-0.043093	9.777271	0.046231	0.089132	-0.038104
+2.546447	0.019152	-0.007182	9.834729	0.046897	0.085534	-0.035972
+2.547382	-0.007182	0.035911	9.801212	0.046631	0.085934	-0.035839
+2.548447	0.014364	0.014364	9.861063	0.046764	0.087400	-0.035706
+2.549446	-0.011970	-0.023940	9.777271	0.048230	0.088066	-0.038371
+2.550417	0.043093	-0.045487	9.748543	0.047430	0.086201	-0.037704
+2.551384	-0.007182	-0.016758	9.817970	0.048363	0.085668	-0.035972
+2.552447	-0.031123	0.002394	9.849093	0.046631	0.088732	-0.036905
+2.553450	0.028729	-0.045487	9.798818	0.045698	0.089265	-0.039303
+2.554450	0.026334	-0.059851	9.789242	0.047564	0.087666	-0.039969
+2.555446	0.000000	-0.004788	9.813182	0.048629	0.085934	-0.039570
+2.556377	0.016758	0.040699	9.813182	0.049029	0.086334	-0.038637
+2.557445	-0.074215	0.000000	9.849093	0.049828	0.084335	-0.039170
+2.558451	-0.076609	0.000000	9.853881	0.048496	0.086467	-0.043034
+2.559446	-0.016758	-0.019152	9.875427	0.048096	0.087933	-0.039836
+2.560440	0.004788	-0.002394	9.782060	0.049962	0.090464	-0.035706
+2.561406	0.016758	0.023940	9.724603	0.047564	0.091397	-0.034374
+2.562446	0.021546	0.026334	9.803606	0.044766	0.089398	-0.033041
+2.563444	0.031123	-0.047881	9.911338	0.043167	0.086867	-0.033974
+2.564397	0.055063	-0.004788	9.837123	0.044766	0.087400	-0.034507
+2.565376	-0.019152	-0.059851	9.798818	0.046098	0.088466	-0.035706
+2.566411	0.050275	-0.093368	9.873033	0.048096	0.086734	-0.039303
+2.567381	0.011970	-0.028729	9.791636	0.047031	0.088066	-0.038371
+2.568446	-0.026334	0.002394	9.827546	0.046364	0.087666	-0.035573
+2.569367	0.050275	-0.004788	9.846699	0.045965	0.088732	-0.033308
+2.570384	0.040699	-0.021546	9.870639	0.044632	0.089398	-0.035706
+2.571380	0.004788	0.002394	9.765301	0.044899	0.085268	-0.037838
+2.572380	-0.014364	0.009576	9.767695	0.045965	0.086067	-0.039969
+2.573379	0.033517	-0.009576	9.832334	0.045832	0.088466	-0.038904
+2.574358	0.043093	-0.014364	9.820364	0.046231	0.090597	-0.037172
+2.575383	0.043093	0.004788	9.794030	0.045565	0.090198	-0.035440
+2.576381	0.031123	-0.026334	9.779666	0.047430	0.087666	-0.036372
+2.577442	0.014364	0.023940	9.844305	0.046498	0.086867	-0.035040
+2.578389	-0.031123	0.019152	9.806000	0.044899	0.088332	-0.033974
+2.579385	-0.004788	0.007182	9.858669	0.045032	0.087000	-0.034240
+2.580385	-0.004788	-0.050275	9.841911	0.046364	0.087133	-0.036239
+2.581446	-0.021546	-0.079003	9.774877	0.046231	0.087133	-0.039703
+2.582446	0.014364	-0.033517	9.777271	0.046364	0.088466	-0.035306
+2.583447	-0.002394	-0.038305	9.777271	0.044766	0.090064	-0.032775
+2.584383	-0.014364	-0.090974	9.758119	0.045565	0.088066	-0.036772
+2.585377	-0.009576	-0.098156	9.722208	0.046231	0.087666	-0.036505
+2.586413	-0.004788	-0.040699	9.698268	0.047164	0.084868	-0.037172
+2.587448	-0.033517	-0.038305	9.774877	0.049029	0.084602	-0.035440
+2.588446	-0.007182	-0.011970	9.791636	0.046897	0.084335	-0.037838
+2.589446	0.038305	-0.023940	9.822758	0.046098	0.085002	-0.036905
+2.590450	0.009576	-0.062245	9.798818	0.049296	0.086600	-0.037305
+2.591446	0.043093	-0.052669	9.798818	0.049962	0.088199	-0.039436
+2.592383	0.011970	0.007182	9.748543	0.047564	0.089132	-0.035040
+2.593446	0.014364	-0.035911	9.820364	0.046364	0.089665	-0.035173
+2.594385	-0.038305	-0.016758	9.882609	0.046631	0.086600	-0.036772
+2.595438	-0.004788	-0.038305	9.801212	0.046498	0.086067	-0.035440
+2.596447	-0.011970	-0.021546	9.817970	0.048363	0.090864	-0.038637
+2.597447	0.009576	0.014364	9.755725	0.047697	0.091663	-0.038637
+2.598449	-0.009576	-0.031123	9.813182	0.045965	0.087266	-0.038904
+2.599448	-0.079003	0.014364	9.829940	0.046897	0.085135	-0.038637
+2.600398	-0.031123	-0.045487	9.822758	0.046631	0.087266	-0.039570
+2.601387	0.021546	0.007182	9.899368	0.046364	0.088199	-0.040236
+2.602382	0.035911	-0.019152	9.827546	0.048496	0.087799	-0.037571
+2.603400	0.023940	0.016758	9.813182	0.049162	0.088998	-0.034640
+2.604440	-0.038305	-0.002394	9.825152	0.047963	0.086600	-0.034240
+2.605399	0.004788	-0.009576	9.918520	0.048230	0.087533	-0.037305
+2.606451	-0.009576	0.062245	9.794030	0.047564	0.088199	-0.038770
+2.607445	0.021546	0.045487	9.715026	0.048763	0.088732	-0.038104
+2.608446	0.045487	0.007182	9.832334	0.048763	0.088332	-0.035440
+2.609390	0.002394	-0.081397	9.820364	0.047564	0.090064	-0.036372
+2.610447	0.014364	-0.052669	9.825152	0.045565	0.088998	-0.036772
+2.611447	0.019152	-0.031123	9.829940	0.047697	0.087666	-0.037038
+2.612384	0.038305	-0.062245	9.784454	0.048629	0.088066	-0.037971
+2.613359	0.004788	-0.052669	9.760513	0.048496	0.088466	-0.039170
+2.614378	0.019152	0.007182	9.846699	0.047963	0.088998	-0.037704
+2.615448	0.009576	-0.014364	9.851487	0.049029	0.087933	-0.034773
+2.616446	0.011970	-0.033517	9.851487	0.046231	0.086600	-0.036239
+2.617383	-0.031123	-0.038305	9.834729	0.046098	0.087400	-0.039303
+2.618353	-0.007182	-0.045487	9.731785	0.046364	0.089931	-0.037971
+2.619447	0.019152	-0.038305	9.762907	0.046364	0.090198	-0.033708
+2.620446	-0.028729	-0.064639	9.774877	0.046764	0.089132	-0.031043
+2.621400	0.000000	0.035911	9.825152	0.048496	0.085934	-0.035706
+2.622415	-0.023940	0.038305	9.849093	0.046231	0.085934	-0.041168
+2.623448	-0.055063	0.009576	9.794030	0.046364	0.086201	-0.038104
+2.624448	-0.069427	0.007182	9.820364	0.047564	0.085801	-0.033574
+2.625373	0.035911	-0.016758	9.806000	0.046231	0.086334	-0.033974
+2.626450	-0.002394	-0.062245	9.796424	0.045965	0.088865	-0.034907
+2.627447	-0.038305	-0.040699	9.772483	0.048896	0.089265	-0.038237
+2.628447	-0.009576	-0.011970	9.758119	0.046364	0.084469	-0.037704
+2.629456	0.000000	-0.019152	9.815576	0.045832	0.086067	-0.038104
+2.630405	-0.007182	0.040699	9.829940	0.046498	0.089665	-0.040369
+2.631444	-0.014364	-0.023940	9.813182	0.046098	0.088865	-0.038104
+2.632449	0.000000	-0.009576	9.789242	0.044899	0.086600	-0.039303
+2.633450	0.007182	-0.004788	9.832334	0.047830	0.086067	-0.037172
+2.634385	0.019152	-0.004788	9.817970	0.048096	0.087266	-0.035706
+2.635355	0.019152	-0.004788	9.817970	0.046897	0.088066	-0.035706
+2.636447	-0.021546	-0.011970	9.851487	0.046098	0.087933	-0.033841
+2.637448	-0.009576	-0.047881	9.779666	0.048363	0.086734	-0.035306
+2.638403	-0.047881	-0.057457	9.798818	0.048763	0.088599	-0.036239
+2.639402	0.023940	-0.059851	9.896974	0.049029	0.089132	-0.032908
+2.640447	0.064639	-0.035911	9.798818	0.048896	0.090064	-0.034907
+2.641450	0.038305	0.011970	9.791636	0.045698	0.090198	-0.038904
+2.642452	0.050275	-0.019152	9.906550	0.045698	0.088599	-0.037971
+2.643449	0.038305	-0.004788	9.863457	0.046498	0.084735	-0.035706
+2.644447	0.028729	0.016758	9.901762	0.046897	0.087666	-0.036372
+2.645446	0.045487	0.004788	9.875427	0.045965	0.090064	-0.037038
+2.646447	0.081397	0.021546	9.820364	0.046098	0.088732	-0.034773
+2.647401	0.038305	0.033517	9.827546	0.046098	0.088332	-0.031176
+2.648436	0.019152	0.011970	9.868245	0.046098	0.089665	-0.033841
+2.649385	0.009576	0.040699	9.837123	0.046897	0.090597	-0.034640
+2.650448	0.019152	0.011970	9.870639	0.048363	0.089798	-0.035440
+2.651388	-0.004788	0.026334	9.844305	0.046764	0.087933	-0.038237
+2.652382	0.019152	0.033517	9.710238	0.045165	0.087266	-0.039037
+2.653445	-0.026334	0.038305	9.808394	0.045965	0.088199	-0.035839
+2.654402	-0.014364	-0.011970	9.791636	0.045965	0.088332	-0.035706
+2.655442	0.050275	0.000000	9.782060	0.045032	0.085934	-0.037704
+2.656443	0.026334	-0.014364	9.755725	0.043700	0.085135	-0.038237
+2.657398	0.026334	-0.002394	9.827546	0.044632	0.087799	-0.036772
+2.658438	0.007182	0.000000	9.762907	0.048363	0.089798	-0.035040
+2.659435	-0.016758	-0.007182	9.767695	0.048363	0.089798	-0.037571
+2.660445	-0.045487	-0.002394	9.820364	0.044233	0.088199	-0.036239
+2.661446	0.019152	-0.019152	9.829940	0.045032	0.087000	-0.036106
+2.662450	0.038305	-0.009576	9.750937	0.045965	0.087266	-0.035173
+2.663446	0.019152	0.002394	9.779666	0.047297	0.087666	-0.034507
+2.664408	0.052669	-0.007182	9.801212	0.047697	0.088066	-0.036905
+2.665384	0.016758	-0.016758	9.820364	0.046897	0.085002	-0.039570
+2.666401	0.009576	0.011970	9.863457	0.045965	0.087133	-0.035573
+2.667369	0.016758	-0.014364	9.873033	0.046897	0.089665	-0.032642
+2.668393	-0.045487	-0.031123	9.882609	0.048496	0.087533	-0.034907
+2.669445	0.021546	-0.011970	9.796424	0.046364	0.087000	-0.037971
+2.670388	0.062245	0.038305	9.758119	0.044499	0.086734	-0.037305
+2.671383	0.021546	-0.002394	9.846699	0.045565	0.087933	-0.037838
+2.672383	-0.028729	-0.019152	9.789242	0.047430	0.086867	-0.036239
+2.673444	-0.004788	-0.004788	9.791636	0.048896	0.088332	-0.032375
+2.674381	0.023940	-0.033517	9.856275	0.048230	0.089132	-0.034240
+2.675372	0.004788	-0.011970	9.846699	0.045965	0.086867	-0.037438
+2.676399	-0.011970	-0.002394	9.839517	0.046364	0.089398	-0.034240
+2.677421	-0.002394	-0.011970	9.762907	0.046897	0.091263	-0.034907
+2.678386	-0.007182	0.002394	9.755725	0.046364	0.090597	-0.036372
+2.679388	-0.002394	0.028729	9.803606	0.048230	0.088732	-0.035440
+2.680446	0.014364	0.031123	9.767695	0.046231	0.089931	-0.036372
+2.681445	0.047881	-0.088580	9.801212	0.045565	0.090064	-0.037838
+2.682448	0.088580	-0.031123	9.837123	0.046098	0.087266	-0.035306
+2.683444	0.000000	0.002394	9.806000	0.048230	0.087533	-0.035440
+2.684443	0.023940	0.021546	9.738967	0.049029	0.089665	-0.036905
+2.685360	0.079003	-0.014364	9.762907	0.046631	0.089265	-0.035173
+2.686413	-0.014364	-0.031123	9.827546	0.047297	0.086600	-0.035306
+2.687386	-0.045487	-0.052669	9.731785	0.048096	0.084735	-0.037038
+2.688392	0.035911	0.031123	9.717420	0.046364	0.085934	-0.039836
+2.689446	0.033517	0.057457	9.758119	0.045299	0.087933	-0.038904
+2.690376	0.038305	0.023940	9.741361	0.047297	0.087400	-0.036239
+2.691445	-0.009576	0.000000	9.794030	0.048629	0.088332	-0.036106
+2.692440	-0.067033	0.045487	9.817970	0.049029	0.088466	-0.036639
+2.693384	0.002394	-0.045487	9.885003	0.047830	0.089531	-0.038104
+2.694369	0.023940	-0.026334	9.853881	0.047164	0.089931	-0.037438
+2.695400	0.021546	-0.040699	9.827546	0.047697	0.089798	-0.037038
+2.696409	0.038305	-0.031123	9.772483	0.046364	0.088332	-0.033308
+2.697445	0.033517	-0.007182	9.849093	0.045832	0.085801	-0.035440
+2.698450	0.045487	0.043093	9.825152	0.049029	0.085934	-0.036772
+2.699444	-0.009576	0.014364	9.808394	0.047963	0.089531	-0.034240
+2.700446	0.028729	0.043093	9.813182	0.046631	0.090198	-0.035706
+2.701446	0.028729	0.007182	9.834729	0.045965	0.088066	-0.035972
+2.702386	-0.009576	-0.016758	9.849093	0.045432	0.086867	-0.035306
+2.703400	-0.026334	0.019152	9.829940	0.045432	0.088998	-0.037438
+2.704401	-0.038305	-0.009576	9.839517	0.049429	0.086600	-0.037704
+2.705432	-0.016758	-0.014364	9.849093	0.049162	0.086600	-0.037172
+2.706449	0.002394	0.038305	9.856275	0.048629	0.087933	-0.038237
+2.707378	-0.019152	0.050275	9.750937	0.045832	0.087533	-0.037038
+2.708447	-0.045487	-0.009576	9.748543	0.044366	0.086067	-0.034773
+2.709445	-0.014364	-0.033517	9.755725	0.045832	0.087133	-0.034640
+2.710363	0.059851	0.028729	9.825152	0.049296	0.089132	-0.038371
+2.711445	0.033517	0.033517	9.767695	0.049562	0.087933	-0.035040
+2.712444	0.038305	0.016758	9.808394	0.048363	0.087533	-0.034907
+2.713401	0.021546	0.000000	9.839517	0.046498	0.090730	-0.035040
+2.714365	0.040699	0.026334	9.892186	0.045832	0.090997	-0.036639
+2.715385	-0.004788	-0.040699	9.796424	0.045965	0.087933	-0.038637
+2.716445	0.014364	0.004788	9.724603	0.048363	0.084069	-0.036239
+2.717367	-0.043093	0.007182	9.765301	0.048496	0.085934	-0.035839
+2.718377	-0.064639	-0.033517	9.743755	0.045832	0.087533	-0.036372
+2.719444	-0.002394	-0.043093	9.786848	0.047297	0.087266	-0.037438
+2.720444	0.019152	-0.064639	9.808394	0.047830	0.087933	-0.036505
+2.721393	-0.002394	-0.069427	9.782060	0.048230	0.088466	-0.037038
+2.722404	0.009576	-0.043093	9.808394	0.048096	0.090597	-0.037704
+2.723400	-0.002394	0.000000	9.856275	0.047031	0.088599	-0.039969
+2.724403	0.021546	0.031123	9.844305	0.047164	0.086467	-0.039969
+2.725388	0.033517	-0.014364	9.882609	0.047830	0.087666	-0.037305
+2.726446	-0.045487	-0.016758	9.779666	0.050228	0.088998	-0.033708
+2.727444	-0.011970	-0.028729	9.808394	0.048496	0.088466	-0.036772
+2.728442	0.028729	0.019152	9.841911	0.046498	0.090064	-0.037038
+2.729443	0.016758	0.000000	9.834729	0.044899	0.088599	-0.036372
+2.730447	0.021546	-0.004788	9.839517	0.046897	0.088599	-0.039703
+2.731373	-0.009576	-0.035911	9.815576	0.049562	0.085268	-0.036639
+2.732441	-0.023940	-0.033517	9.719814	0.048763	0.082470	-0.037838
+2.733443	0.026334	-0.009576	9.810788	0.047031	0.085135	-0.037305
+2.734447	-0.011970	0.019152	9.750937	0.045565	0.089931	-0.037838
+2.735383	-0.062245	-0.023940	9.791636	0.047963	0.090597	-0.036106
+2.736380	-0.002394	0.002394	9.825152	0.049162	0.090198	-0.036905
+2.737371	0.031123	-0.011970	9.829940	0.045832	0.088199	-0.037704
+2.738350	-0.040699	0.007182	9.798818	0.045299	0.086867	-0.033175
+2.739378	-0.069427	0.007182	9.841911	0.044100	0.084735	-0.035040
+2.740352	0.002394	0.040699	9.839517	0.045565	0.085668	-0.038904
+2.741375	0.035911	0.033517	9.870639	0.047297	0.088199	-0.039436
+2.742376	0.014364	-0.004788	9.913732	0.048496	0.086867	-0.034507
+2.743451	0.021546	-0.014364	9.896974	0.049162	0.085135	-0.034507
+2.744445	0.002394	-0.004788	9.796424	0.047164	0.085534	-0.035306
+2.745423	0.004788	0.011970	9.784454	0.047430	0.086201	-0.038770
+2.746448	-0.014364	-0.050275	9.806000	0.046231	0.087799	-0.037704
+2.747446	0.055063	-0.014364	9.861063	0.045965	0.087933	-0.034640
+2.748448	0.045487	0.016758	9.784454	0.047697	0.087933	-0.033841
+2.749445	0.011970	-0.033517	9.743755	0.047164	0.087533	-0.036639
+2.750402	-0.014364	0.000000	9.748543	0.046364	0.088599	-0.039570
+2.751381	-0.021546	0.014364	9.784454	0.045832	0.086334	-0.036905
+2.752382	-0.007182	-0.033517	9.794030	0.048496	0.088332	-0.036639
+2.753446	0.019152	-0.050275	9.760513	0.046631	0.091930	-0.034640
+2.754428	0.002394	0.000000	9.815576	0.044499	0.088998	-0.031043
+2.755444	-0.007182	0.009576	9.789242	0.044499	0.083136	-0.035306
+2.756443	-0.023940	-0.023940	9.796424	0.047297	0.082470	-0.039703
+2.757445	0.016758	-0.031123	9.789242	0.050761	0.086734	-0.039969
+2.758445	0.014364	0.009576	9.750937	0.049828	0.089132	-0.040369
+2.759447	0.076609	0.021546	9.791636	0.048496	0.088199	-0.034640
+2.760376	0.043093	-0.026334	9.774877	0.049695	0.088332	-0.034507
+2.761442	-0.040699	-0.059851	9.858669	0.050095	0.088332	-0.032375
+2.762448	-0.026334	-0.045487	9.856275	0.046498	0.087533	-0.034107
+2.763446	0.016758	-0.033517	9.794030	0.047297	0.085268	-0.035573
+2.764445	0.004788	-0.088580	9.829940	0.048363	0.086734	-0.035440
+2.765399	-0.040699	-0.062245	9.770089	0.047697	0.088998	-0.037971
+2.766447	-0.026334	-0.023940	9.767695	0.047963	0.090331	-0.039570
+2.767379	-0.079003	-0.028729	9.796424	0.047963	0.090597	-0.039170
+2.768379	0.016758	-0.009576	9.789242	0.045965	0.087533	-0.039037
+2.769379	0.040699	-0.019152	9.717420	0.047430	0.086467	-0.036905
+2.770347	-0.023940	-0.019152	9.815576	0.048763	0.084602	-0.033708
+2.771381	0.019152	0.011970	9.837123	0.048629	0.087666	-0.033041
+2.772378	0.067033	0.014364	9.844305	0.048763	0.089531	-0.032242
+2.773378	0.000000	0.009576	9.813182	0.047430	0.088332	-0.030110
+2.774375	0.083792	0.043093	9.817970	0.045165	0.088066	-0.031043
+2.775379	0.069427	0.004788	9.817970	0.045165	0.087933	-0.034773
+2.776379	0.055063	-0.069427	9.861063	0.047031	0.088732	-0.034773
+2.777380	0.064639	-0.035911	9.822758	0.047697	0.090597	-0.033708
+2.778355	0.076609	0.047881	9.772483	0.048763	0.089931	-0.033974
+2.779378	-0.031123	0.004788	9.743755	0.047564	0.086600	-0.037172
+2.780377	-0.040699	-0.002394	9.829940	0.047564	0.083936	-0.038637
+2.781346	-0.026334	-0.007182	9.794030	0.048763	0.085801	-0.037571
+2.782375	-0.011970	0.028729	9.784454	0.047697	0.088998	-0.039836
+2.783378	0.007182	-0.033517	9.777271	0.047297	0.089798	-0.033841
+2.784378	0.031123	-0.007182	9.765301	0.047430	0.087400	-0.033441
+2.785380	-0.031123	-0.019152	9.734179	0.047564	0.085401	-0.033974
+2.786382	-0.031123	0.019152	9.791636	0.047297	0.085268	-0.034107
+2.787378	-0.023940	0.011970	9.796424	0.045432	0.085401	-0.037438
+2.788379	-0.033517	0.004788	9.743755	0.047430	0.087799	-0.039703
+2.789378	0.009576	-0.002394	9.815576	0.049162	0.090864	-0.037838
+2.790379	0.043093	0.014364	9.844305	0.047564	0.092196	-0.037571
+2.791379	-0.004788	0.043093	9.777271	0.047697	0.089665	-0.036372
+2.792349	-0.021546	0.035911	9.743755	0.048363	0.086600	-0.037438
+2.793382	0.004788	-0.021546	9.777271	0.048763	0.087666	-0.036106
+2.794350	0.059851	-0.009576	9.758119	0.047430	0.088466	-0.035173
+2.795381	0.064639	-0.062245	9.789242	0.047297	0.089132	-0.037438
+2.796374	0.110126	-0.040699	9.786848	0.049162	0.088599	-0.037305
+2.797378	0.079003	-0.016758	9.834729	0.048496	0.087400	-0.035173
+2.798385	0.052669	-0.004788	9.796424	0.048363	0.084202	-0.035972
+2.799443	0.019152	0.004788	9.786848	0.046764	0.087266	-0.040769
+2.800376	-0.019152	0.021546	9.801212	0.046098	0.090198	-0.037571
+2.801360	0.040699	0.011970	9.803606	0.047164	0.091397	-0.033574
+2.802394	0.007182	0.011970	9.803606	0.047564	0.090198	-0.034773
+2.803423	0.023940	-0.021546	9.798818	0.050095	0.086334	-0.033574
+2.804432	-0.033517	0.000000	9.829940	0.049162	0.086201	-0.036239
+2.805443	-0.016758	-0.023940	9.789242	0.046631	0.087533	-0.033708
+2.806445	-0.031123	-0.014364	9.777271	0.046498	0.088466	-0.035040
+2.807447	-0.016758	-0.011970	9.772483	0.045299	0.088732	-0.035040
+2.808443	0.043093	-0.021546	9.796424	0.047830	0.086467	-0.034107
+2.809443	0.007182	-0.002394	9.774877	0.048230	0.084069	-0.031443
+2.810386	-0.021546	-0.011970	9.827546	0.045698	0.084735	-0.033441
+2.811378	-0.019152	-0.002394	9.822758	0.044766	0.084602	-0.034507
+2.812416	0.033517	-0.002394	9.808394	0.045698	0.085268	-0.034640
+2.813446	0.023940	-0.031123	9.827546	0.047430	0.089665	-0.036106
+2.814446	0.064639	-0.014364	9.837123	0.049029	0.090997	-0.040369
+2.815398	0.026334	0.011970	9.846699	0.047164	0.090064	-0.039303
+2.816443	-0.026334	-0.011970	9.717420	0.042634	0.087799	-0.039436
+2.817387	0.076609	0.014364	9.762907	0.044499	0.086201	-0.039570
+2.818377	0.021546	0.007182	9.817970	0.047297	0.088332	-0.035706
+2.819442	-0.026334	0.000000	9.825152	0.048096	0.089265	-0.031309
+2.820391	-0.016758	0.004788	9.832334	0.048896	0.089398	-0.033441
+2.821435	0.004788	-0.016758	9.765301	0.046364	0.090064	-0.036106
+2.822446	0.009576	0.002394	9.784454	0.045165	0.089265	-0.040502
+2.823442	-0.040699	0.007182	9.849093	0.044766	0.088332	-0.040902
+2.824397	-0.023940	-0.019152	9.806000	0.044632	0.088332	-0.037438
+2.825444	0.009576	-0.055063	9.806000	0.048096	0.088066	-0.036239
+2.826444	0.009576	-0.026334	9.801212	0.048363	0.088599	-0.035839
+2.827444	-0.050275	0.028729	9.863457	0.048096	0.088466	-0.032508
+2.828443	0.011970	0.062245	9.703056	0.048496	0.087933	-0.035040
+2.829388	0.002394	0.023940	9.734179	0.045965	0.089398	-0.038504
+2.830441	0.009576	0.023940	9.875427	0.043567	0.088599	-0.034907
+2.831443	0.083792	-0.019152	9.973583	0.043034	0.086867	-0.038104
+2.832444	0.021546	-0.038305	9.863457	0.043433	0.086734	-0.038637
+2.833402	0.038305	0.019152	9.796424	0.045965	0.089798	-0.037971
+2.834447	-0.019152	0.011970	9.712632	0.049296	0.090064	-0.037838
+2.835384	0.004788	-0.023940	9.746149	0.046764	0.085135	-0.034640
+2.836441	0.007182	-0.009576	9.839517	0.045432	0.084868	-0.036106
+2.837442	-0.031123	0.023940	9.767695	0.043700	0.086067	-0.035706
+2.838377	0.031123	-0.026334	9.743755	0.045565	0.086334	-0.036372
+2.839442	-0.023940	-0.047881	9.806000	0.047564	0.088732	-0.036505
+2.840442	-0.021546	-0.023940	9.825152	0.048363	0.087933	-0.035972
+2.841445	0.023940	-0.026334	9.806000	0.046098	0.084735	-0.035573
+2.842446	0.033517	-0.023940	9.829940	0.046631	0.087533	-0.035440
+2.843442	0.000000	-0.023940	9.832334	0.047031	0.090997	-0.035706
+2.844400	-0.028729	-0.007182	9.817970	0.046364	0.092462	-0.036106
+2.845441	-0.009576	0.004788	9.810788	0.048363	0.088199	-0.034773
+2.846423	-0.028729	-0.009576	9.837123	0.049429	0.085801	-0.036372
+2.847377	-0.038305	-0.009576	9.827546	0.047830	0.086201	-0.038371
+2.848445	0.033517	0.000000	9.762907	0.046764	0.089798	-0.037704
+2.849402	-0.009576	0.007182	9.827546	0.044632	0.090464	-0.035839
+2.850443	0.007182	0.023940	9.817970	0.043966	0.086334	-0.033974
+2.851372	0.002394	-0.004788	9.834729	0.044233	0.083403	-0.035839
+2.852381	0.069427	0.023940	9.834729	0.048096	0.085002	-0.036239
+2.853378	0.067033	-0.004788	9.803606	0.051161	0.086734	-0.036905
+2.854378	0.038305	0.028729	9.772483	0.049162	0.088599	-0.036106
+2.855397	-0.021546	0.007182	9.810788	0.046764	0.090864	-0.037172
+2.856388	-0.038305	-0.009576	9.837123	0.046098	0.089265	-0.037971
+2.857433	0.021546	-0.064639	9.868245	0.048096	0.088466	-0.035972
+2.858447	0.014364	-0.069427	9.794030	0.047164	0.088865	-0.036772
+2.859444	0.026334	-0.069427	9.712632	0.043567	0.087266	-0.035173
+2.860442	0.050275	-0.055063	9.695874	0.043167	0.087933	-0.037305
+2.861443	0.033517	-0.016758	9.808394	0.042501	0.087266	-0.040103
+2.862454	0.002394	-0.023940	9.738967	0.044632	0.086467	-0.040502
+2.863443	-0.033517	0.002394	9.731785	0.046498	0.087000	-0.033175
+2.864442	-0.011970	0.023940	9.851487	0.047564	0.086867	-0.034107
+2.865385	-0.014364	0.023940	9.899368	0.047164	0.088066	-0.036106
+2.866442	0.055063	0.033517	9.858669	0.046764	0.089531	-0.035839
+2.867403	-0.011970	0.011970	9.846699	0.047164	0.089665	-0.035306
+2.868373	-0.057457	0.004788	9.820364	0.047430	0.085668	-0.034107
+2.869378	-0.011970	-0.009576	9.803606	0.049828	0.085534	-0.037038
+2.870447	-0.040699	-0.002394	9.832334	0.048629	0.088199	-0.038637
+2.871443	-0.067033	0.009576	9.820364	0.047297	0.087133	-0.033708
+2.872443	-0.004788	-0.040699	9.779666	0.049562	0.083669	-0.031975
+2.873376	0.026334	-0.028729	9.849093	0.048496	0.086334	-0.034773
+2.874373	0.021546	-0.033517	9.806000	0.046631	0.088332	-0.038104
+2.875417	0.004788	-0.002394	9.736573	0.047031	0.089265	-0.039170
+2.876387	-0.002394	-0.009576	9.755725	0.047697	0.090997	-0.037571
+2.877443	0.035911	0.043093	9.767695	0.047697	0.086867	-0.035972
+2.878466	0.043093	0.023940	9.813182	0.047564	0.087666	-0.033841
+2.879442	0.026334	-0.011970	9.820364	0.046231	0.087666	-0.036639
+2.880403	0.033517	0.000000	9.837123	0.046631	0.086334	-0.040369
+2.881383	0.043093	-0.038305	9.837123	0.046498	0.087266	-0.039969
+2.882383	0.035911	-0.021546	9.803606	0.046764	0.087266	-0.038371
+2.883443	0.050275	0.000000	9.817970	0.048763	0.085801	-0.037571
+2.884386	0.016758	-0.023940	9.849093	0.050228	0.086867	-0.037571
+2.885385	0.009576	-0.031123	9.774877	0.050894	0.090464	-0.037704
+2.886444	0.026334	-0.016758	9.822758	0.048629	0.089132	-0.035440
+2.887442	-0.033517	0.043093	9.782060	0.044366	0.083936	-0.036905
+2.888442	-0.023940	-0.062245	9.786848	0.046098	0.083536	-0.038104
+2.889443	-0.057457	-0.059851	9.858669	0.047297	0.086467	-0.034773
+2.890446	-0.079003	0.000000	9.837123	0.045165	0.089931	-0.035173
+2.891442	0.040699	-0.019152	9.863457	0.042767	0.090331	-0.036505
+2.892442	0.038305	-0.004788	9.894580	0.044899	0.088332	-0.037038
+2.893394	0.011970	0.016758	9.801212	0.047430	0.087799	-0.035839
+2.894360	-0.004788	0.004788	9.762907	0.045832	0.089265	-0.036772
+2.895444	0.007182	-0.014364	9.791636	0.047297	0.087933	-0.036106
+2.896446	0.028729	-0.007182	9.806000	0.048096	0.086467	-0.034640
+2.897380	-0.031123	-0.004788	9.784454	0.047830	0.085002	-0.035972
+2.898376	-0.071821	-0.035911	9.829940	0.047564	0.088066	-0.037438
+2.899443	-0.023940	-0.009576	9.803606	0.044499	0.089798	-0.034773
+2.900441	0.076609	-0.011970	9.820364	0.045299	0.089798	-0.033175
+2.901440	0.102944	-0.023940	9.789242	0.048496	0.087266	-0.037971
+2.902394	-0.007182	-0.009576	9.786848	0.049962	0.086201	-0.042101
+2.903397	-0.023940	0.007182	9.880215	0.047564	0.087666	-0.037172
+2.904398	-0.040699	0.002394	9.829940	0.047430	0.089265	-0.033441
+2.905451	-0.055063	-0.035911	9.820364	0.047297	0.088599	-0.032908
+2.906404	0.004788	0.016758	9.815576	0.046364	0.088732	-0.037305
+2.907442	0.016758	0.014364	9.825152	0.045965	0.087799	-0.036772
+2.908442	0.011970	0.014364	9.858669	0.046498	0.087666	-0.036106
+2.909441	0.055063	-0.009576	9.803606	0.048363	0.085934	-0.035573
+2.910379	0.007182	-0.004788	9.777271	0.049029	0.085534	-0.039570
+2.911390	-0.023940	-0.033517	9.841911	0.048896	0.087000	-0.040103
+2.912413	-0.023940	-0.026334	9.801212	0.045965	0.088998	-0.037438
+2.913386	-0.016758	-0.031123	9.827546	0.043966	0.088599	-0.035573
+2.914360	0.014364	-0.031123	9.837123	0.046897	0.089132	-0.037172
+2.915442	0.038305	-0.009576	9.875427	0.048629	0.086067	-0.035306
+2.916379	0.000000	-0.016758	9.861063	0.044233	0.086334	-0.036372
+2.917360	0.031123	0.002394	9.822758	0.045565	0.087799	-0.034107
+2.918375	0.023940	-0.028729	9.767695	0.048896	0.088199	-0.035173
+2.919370	0.000000	-0.009576	9.786848	0.049562	0.088732	-0.036106
+2.920371	-0.009576	-0.002394	9.801212	0.048230	0.089398	-0.037172
+2.921370	0.067033	-0.081397	9.834729	0.046231	0.090597	-0.037172
+2.922371	0.004788	-0.035911	9.825152	0.044766	0.088332	-0.037172
+2.923367	-0.038305	0.009576	9.810788	0.043433	0.089132	-0.035573
+2.924399	-0.021546	0.081397	9.741361	0.044899	0.089798	-0.035573
+2.925394	-0.002394	0.035911	9.753331	0.045432	0.088732	-0.034374
+2.926445	-0.016758	0.035911	9.827546	0.046098	0.087266	-0.038371
+2.927386	-0.064639	0.021546	9.829940	0.047697	0.088066	-0.035306
+2.928445	-0.050275	-0.014364	9.846699	0.047963	0.086467	-0.033308
+2.929404	-0.035911	-0.019152	9.834729	0.047564	0.088066	-0.036239
+2.930442	0.004788	-0.004788	9.765301	0.047963	0.088066	-0.038637
+2.931380	0.081397	0.000000	9.743755	0.045965	0.088332	-0.039170
+2.932370	0.057457	0.014364	9.748543	0.045432	0.089531	-0.040103
+2.933371	0.016758	0.038305	9.743755	0.047564	0.090730	-0.039703
+2.934323	0.004788	-0.004788	9.820364	0.048763	0.089265	-0.036372
+2.935338	0.000000	0.011970	9.849093	0.046498	0.085401	-0.036372
+2.936399	0.045487	-0.016758	9.803606	0.044100	0.087000	-0.035573
+2.937400	-0.011970	0.002394	9.832334	0.045032	0.093795	-0.037971
+2.938400	0.026334	0.023940	9.846699	0.047697	0.092063	-0.038904
+2.939389	0.062245	-0.033517	9.844305	0.048096	0.088332	-0.037571
+2.940399	0.004788	0.011970	9.794030	0.047697	0.085268	-0.033974
+2.941398	0.004788	-0.026334	9.822758	0.046897	0.085934	-0.036372
+2.942398	0.031123	-0.052669	9.829940	0.045432	0.088599	-0.041435
+2.943378	0.011970	-0.035911	9.825152	0.043567	0.090997	-0.037704
+2.944323	-0.035911	-0.031123	9.791636	0.044766	0.089531	-0.037038
+2.945396	0.040699	-0.021546	9.806000	0.046631	0.090730	-0.035972
+2.946400	0.028729	-0.004788	9.822758	0.046764	0.088199	-0.036106
+2.947398	0.038305	-0.002394	9.844305	0.045698	0.085268	-0.034240
+2.948375	0.009576	-0.026334	9.755725	0.046631	0.083669	-0.033974
+2.949390	-0.043093	0.014364	9.796424	0.046764	0.084469	-0.035173
+2.950399	-0.031123	0.031123	9.834729	0.047164	0.085801	-0.038237
+2.951333	0.028729	0.007182	9.880215	0.047297	0.087000	-0.037038
+2.952396	0.038305	0.040699	9.827546	0.047031	0.089398	-0.035306
+2.953371	0.038305	-0.004788	9.779666	0.046498	0.089531	-0.034107
+2.954403	0.004788	0.000000	9.794030	0.045165	0.087933	-0.038371
+2.955373	0.004788	-0.019152	9.822758	0.044632	0.088199	-0.037172
+2.956400	-0.028729	0.021546	9.849093	0.045032	0.089265	-0.035040
+2.957399	-0.067033	0.009576	9.846699	0.045432	0.087000	-0.033841
+2.958400	-0.074215	-0.038305	9.849093	0.046764	0.086600	-0.033974
+2.959398	-0.028729	-0.019152	9.810788	0.046098	0.088199	-0.035040
+2.960398	0.045487	-0.007182	9.784454	0.047830	0.089398	-0.037571
+2.961337	0.019152	0.019152	9.861063	0.046231	0.087133	-0.036905
+2.962375	0.009576	-0.014364	9.772483	0.042101	0.086734	-0.037838
+2.963382	0.038305	-0.019152	9.815576	0.045565	0.085934	-0.036639
+2.964398	0.057457	0.002394	9.827546	0.045832	0.087266	-0.037438
+2.965388	0.011970	0.004788	9.863457	0.045299	0.088865	-0.035839
+2.966400	-0.057457	-0.004788	9.856275	0.043567	0.089931	-0.034640
+2.967396	0.014364	0.016758	9.901762	0.046498	0.087933	-0.034374
+2.968327	0.069427	0.002394	9.851487	0.046897	0.084335	-0.032375
+2.969375	0.016758	0.000000	9.782060	0.047297	0.085534	-0.035972
+2.970399	-0.016758	0.000000	9.796424	0.045565	0.088466	-0.039037
+2.971361	0.004788	0.033517	9.746149	0.045698	0.088066	-0.038237
+2.972398	-0.014364	0.002394	9.832334	0.046897	0.086734	-0.036372
+2.973344	0.000000	0.009576	9.832334	0.045832	0.084735	-0.035706
+2.974343	-0.028729	0.009576	9.782060	0.045965	0.084069	-0.036106
+2.975399	-0.043093	-0.028729	9.741361	0.047031	0.085135	-0.038904
+2.976399	-0.011970	-0.076609	9.815576	0.047963	0.087266	-0.038237
+2.977373	0.055063	-0.038305	9.853881	0.047697	0.088998	-0.036905
+2.978400	0.035911	-0.021546	9.829940	0.045698	0.088332	-0.037971
+2.979353	-0.033517	-0.009576	9.746149	0.047297	0.086600	-0.034374
+2.980336	-0.016758	-0.009576	9.774877	0.046897	0.087266	-0.033974
+2.981337	0.055063	-0.014364	9.808394	0.045698	0.090064	-0.034640
+2.982357	0.016758	0.040699	9.849093	0.046098	0.090730	-0.035972
+2.983354	0.031123	-0.043093	9.863457	0.047297	0.087666	-0.036372
+2.984334	-0.009576	-0.057457	9.786848	0.046098	0.088732	-0.037305
+2.985270	-0.021546	-0.038305	9.726997	0.045299	0.088332	-0.035972
+2.986288	0.038305	-0.040699	9.789242	0.046364	0.087266	-0.038104
+2.987286	0.014364	0.033517	9.815576	0.049695	0.085934	-0.036772
+2.988287	-0.064639	0.045487	9.806000	0.048230	0.085934	-0.035972
+2.989310	0.035911	0.000000	9.870639	0.045299	0.084469	-0.039836
+2.990401	0.004788	0.000000	9.853881	0.047164	0.087400	-0.037838
+2.991398	0.028729	-0.045487	9.858669	0.050228	0.089132	-0.035573
+2.992398	0.035911	-0.019152	9.853881	0.047031	0.087666	-0.035306
+2.993375	0.009576	-0.016758	9.813182	0.047297	0.087933	-0.038770
+2.994369	0.043093	0.028729	9.827546	0.047697	0.088599	-0.037571
+2.995394	0.023940	0.019152	9.774877	0.046764	0.088599	-0.035173
+2.996393	0.016758	0.016758	9.755725	0.044366	0.088199	-0.033841
+2.997399	0.002394	-0.004788	9.777271	0.046897	0.090064	-0.035173
+2.998396	0.014364	-0.002394	9.827546	0.046897	0.089132	-0.037971
+2.999398	-0.035911	-0.011970	9.837123	0.046231	0.086467	-0.035972
+3.000398	-0.007182	-0.014364	9.849093	0.047164	0.084602	-0.036772
+3.001343	-0.021546	0.014364	9.796424	0.048230	0.086334	-0.041168
+3.002364	-0.004788	0.050275	9.743755	0.047830	0.089665	-0.040103
+3.003395	-0.004788	0.000000	9.760513	0.044766	0.089798	-0.036239
+3.004356	-0.011970	0.011970	9.870639	0.044233	0.088066	-0.033841
+3.005344	0.026334	-0.014364	9.901762	0.045032	0.086067	-0.035173
+3.006349	0.002394	-0.055063	9.863457	0.046098	0.088066	-0.033974
+3.007338	-0.031123	-0.033517	9.796424	0.048363	0.089665	-0.033308
+3.008367	-0.074215	-0.019152	9.760513	0.050761	0.086867	-0.037571
+3.009415	0.009576	-0.045487	9.794030	0.049029	0.087533	-0.038237
+3.010399	0.033517	-0.031123	9.801212	0.048230	0.086467	-0.038237
+3.011348	0.023940	0.014364	9.734179	0.045832	0.085934	-0.035972
+3.012350	0.059851	-0.067033	9.726997	0.047164	0.087266	-0.037438
+3.013375	0.007182	-0.038305	9.849093	0.047031	0.087799	-0.038504
+3.014346	0.000000	0.016758	9.858669	0.044499	0.089265	-0.039570
+3.015372	-0.004788	-0.021546	9.889792	0.047830	0.089398	-0.040236
+3.016415	0.023940	-0.033517	9.832334	0.050095	0.089398	-0.037172
+3.017354	0.016758	-0.040699	9.841911	0.047164	0.089798	-0.035173
+3.018355	0.007182	0.000000	9.746149	0.046231	0.089531	-0.036505
+3.019413	0.002394	0.035911	9.865851	0.047164	0.091397	-0.036772
+3.020414	0.064639	0.023940	9.861063	0.047031	0.090064	-0.040236
+3.021415	0.059851	0.002394	9.815576	0.047164	0.089398	-0.039037
+3.022417	0.002394	0.023940	9.817970	0.046764	0.088998	-0.037704
+3.023413	0.021546	0.057457	9.777271	0.045165	0.088466	-0.036505
+3.024361	0.028729	0.050275	9.707844	0.043833	0.088199	-0.036905
+3.025357	-0.021546	-0.007182	9.741361	0.045032	0.087933	-0.036905
+3.026355	0.009576	0.002394	9.765301	0.045565	0.083403	-0.037172
+3.027385	0.038305	-0.019152	9.753331	0.045832	0.084735	-0.037704
+3.028412	0.033517	0.002394	9.755725	0.046764	0.088332	-0.037704
+3.029416	0.019152	0.011970	9.851487	0.046631	0.087799	-0.035306
+3.030419	0.083792	-0.016758	9.813182	0.046631	0.088599	-0.033841
+3.031418	0.043093	-0.002394	9.808394	0.045832	0.088998	-0.035972
+3.032416	-0.038305	-0.023940	9.798818	0.044632	0.087266	-0.036905
+3.033419	-0.019152	-0.019152	9.777271	0.044632	0.086067	-0.034773
+3.034303	0.023940	0.035911	9.738967	0.046098	0.087266	-0.034374
+3.035358	0.009576	0.000000	9.784454	0.047164	0.086067	-0.036505
+3.036350	0.067033	0.038305	9.743755	0.047031	0.086067	-0.037038
+3.037346	0.062245	0.038305	9.734179	0.048230	0.087133	-0.038637
+3.038348	0.038305	-0.002394	9.810788	0.047430	0.087400	-0.039170
+3.039345	0.009576	-0.004788	9.786848	0.045299	0.086467	-0.036505
+3.040344	0.019152	0.009576	9.794030	0.044499	0.086201	-0.036106
+3.041347	-0.004788	0.016758	9.791636	0.047830	0.087933	-0.034640
+3.042416	0.040699	-0.014364	9.803606	0.048363	0.087400	-0.035040
+3.043418	0.059851	0.000000	9.750937	0.047031	0.088998	-0.034907
+3.044356	0.090974	-0.019152	9.750937	0.046098	0.089265	-0.037038
+3.045410	0.026334	0.009576	9.817970	0.046364	0.086600	-0.036239
+3.046359	-0.021546	0.045487	9.765301	0.045299	0.086467	-0.035306
+3.047417	-0.023940	0.052669	9.784454	0.047564	0.087933	-0.037172
+3.048414	0.043093	-0.014364	9.808394	0.048363	0.088599	-0.036905
+3.049417	0.047881	0.026334	9.734179	0.047830	0.087666	-0.037038
+3.050418	-0.009576	0.028729	9.784454	0.046631	0.087133	-0.035040
+3.051355	-0.026334	-0.038305	9.810788	0.045965	0.085934	-0.034107
+3.052416	0.021546	-0.011970	9.837123	0.046897	0.086734	-0.037172
+3.053347	0.083792	-0.021546	9.705450	0.046231	0.089132	-0.038504
+3.054371	0.062245	-0.007182	9.784454	0.048096	0.088332	-0.037438
+3.055415	0.009576	0.035911	9.794030	0.046098	0.087133	-0.037438
+3.056416	0.004788	0.007182	9.810788	0.045832	0.085401	-0.036106
+3.057418	0.016758	-0.002394	9.779666	0.044366	0.085934	-0.034374
+3.058420	0.038305	0.009576	9.750937	0.045299	0.088732	-0.033574
+3.059415	0.062245	0.040699	9.779666	0.044233	0.090198	-0.035173
+3.060372	0.002394	0.043093	9.815576	0.046231	0.090730	-0.034507
+3.061416	-0.009576	0.026334	9.851487	0.048496	0.089931	-0.036106
+3.062371	-0.004788	0.014364	9.837123	0.045965	0.089531	-0.036239
+3.063410	0.007182	-0.009576	9.832334	0.045565	0.087400	-0.037438
+3.064374	0.002394	-0.011970	9.784454	0.045432	0.086867	-0.035972
+3.065356	0.026334	0.038305	9.894580	0.046764	0.089132	-0.033574
+3.066354	0.019152	0.009576	9.923308	0.047297	0.091263	-0.034773
+3.067350	-0.011970	-0.007182	9.870639	0.046498	0.087533	-0.032775
+3.068335	-0.019152	0.021546	9.873033	0.048363	0.086600	-0.032508
+3.069415	0.023940	0.014364	9.777271	0.049695	0.087400	-0.034107
+3.070415	0.000000	0.000000	9.806000	0.047697	0.087933	-0.033308
+3.071352	-0.014364	-0.028729	9.861063	0.045432	0.087266	-0.034507
+3.072370	-0.040699	-0.007182	9.829940	0.044100	0.084735	-0.035306
+3.073414	0.019152	0.011970	9.794030	0.044366	0.087400	-0.033574
+3.074358	0.016758	-0.016758	9.782060	0.045032	0.087000	-0.034374
+3.075415	0.016758	0.023940	9.803606	0.046498	0.086067	-0.036772
+3.076353	0.019152	0.021546	9.741361	0.047564	0.086067	-0.035573
+3.077414	0.059851	-0.033517	9.731785	0.046231	0.087266	-0.033708
+3.078419	0.086186	-0.033517	9.841911	0.045299	0.087133	-0.037038
+3.079366	0.057457	-0.033517	9.820364	0.045165	0.087133	-0.038104
+3.080417	0.009576	-0.067033	9.798818	0.045165	0.088466	-0.035440
+3.081373	0.002394	-0.107732	9.832334	0.046498	0.087666	-0.035706
+3.082371	-0.007182	0.000000	9.813182	0.047564	0.087533	-0.035306
+3.083410	0.004788	-0.023940	9.844305	0.047031	0.088732	-0.039303
+3.084427	0.009576	-0.033517	9.825152	0.045565	0.087799	-0.038371
+3.085362	-0.016758	0.009576	9.794030	0.045965	0.087666	-0.036239
+3.086376	0.028729	-0.033517	9.806000	0.045832	0.086201	-0.033974
+3.087413	0.009576	-0.031123	9.801212	0.048496	0.088199	-0.035173
+3.088414	0.004788	-0.019152	9.863457	0.046764	0.089132	-0.038637
+3.089417	0.000000	-0.014364	9.784454	0.043300	0.088332	-0.040369
+3.090372	-0.033517	-0.038305	9.789242	0.044632	0.086734	-0.039703
+3.091418	0.016758	-0.007182	9.837123	0.045832	0.087266	-0.032775
+3.092341	-0.004788	0.002394	9.779666	0.045165	0.088732	-0.034240
+3.093329	-0.014364	-0.028729	9.794030	0.045698	0.088199	-0.036106
+3.094359	0.011970	-0.031123	9.741361	0.046897	0.087133	-0.037438
+3.095415	-0.002394	-0.035911	9.722208	0.046231	0.086600	-0.038770
+3.096413	0.016758	0.026334	9.810788	0.047963	0.086867	-0.039170
+3.097377	-0.023940	0.004788	9.806000	0.046498	0.086600	-0.033574
+3.098354	-0.040699	0.014364	9.865851	0.045832	0.087666	-0.034507
+3.099388	-0.059851	-0.004788	9.885003	0.046364	0.087933	-0.036239
+3.100371	-0.028729	-0.004788	9.841911	0.048230	0.086734	-0.035440
+3.101413	0.004788	-0.026334	9.820364	0.050628	0.086467	-0.034907
+3.102363	-0.004788	-0.002394	9.892186	0.048896	0.087799	-0.039436
+3.103415	0.000000	-0.043093	9.712632	0.048363	0.087933	-0.038371
+3.104414	0.035911	-0.033517	9.731785	0.047830	0.086067	-0.034773
+3.105393	0.055063	0.031123	9.765301	0.046897	0.087666	-0.035173
+3.106415	0.064639	-0.059851	9.765301	0.047963	0.086734	-0.038237
+3.107415	-0.009576	-0.028729	9.810788	0.045565	0.087533	-0.034773
+3.108384	-0.021546	0.011970	9.839517	0.045565	0.089265	-0.035706
+3.109371	-0.064639	0.033517	9.873033	0.048230	0.088466	-0.039303
+3.110363	-0.043093	-0.009576	9.841911	0.049162	0.088599	-0.039703
+3.111358	0.028729	0.000000	9.861063	0.048363	0.089665	-0.042234
+3.112412	0.026334	-0.019152	9.815576	0.048230	0.088998	-0.039303
+3.113417	-0.028729	-0.026334	9.789242	0.048629	0.089931	-0.036505
+3.114371	-0.038305	-0.038305	9.803606	0.047297	0.089665	-0.035440
+3.115414	-0.016758	-0.069427	9.837123	0.046364	0.084735	-0.035573
+3.116414	-0.014364	-0.040699	9.832334	0.045965	0.083270	-0.034640
+3.117369	0.028729	0.026334	9.794030	0.047430	0.085668	-0.036239
+3.118361	0.050275	0.026334	9.801212	0.047564	0.090730	-0.036239
+3.119344	0.071821	0.000000	9.820364	0.046498	0.091130	-0.034240
+3.120414	-0.023940	-0.009576	9.815576	0.045165	0.088865	-0.036639
+3.121415	0.004788	-0.026334	9.779666	0.043433	0.088732	-0.037172
+3.122414	0.019152	0.016758	9.846699	0.045299	0.088865	-0.035440
+3.123413	-0.011970	-0.002394	9.822758	0.049296	0.087799	-0.033041
+3.124374	-0.011970	-0.071821	9.810788	0.049029	0.088066	-0.034907
+3.125413	-0.040699	-0.016758	9.841911	0.048763	0.090064	-0.035839
+3.126425	-0.004788	-0.059851	9.853881	0.045832	0.089665	-0.037038
+3.127374	0.000000	-0.031123	9.784454	0.045432	0.088066	-0.037305
+3.128412	0.050275	-0.002394	9.741361	0.047830	0.088466	-0.037038
+3.129423	0.033517	-0.038305	9.760513	0.048496	0.089798	-0.034640
+3.130414	0.000000	-0.007182	9.849093	0.048629	0.087400	-0.035306
+3.131415	-0.004788	0.007182	9.858669	0.047830	0.086334	-0.035040
+3.132412	0.016758	-0.004788	9.870639	0.048496	0.086867	-0.035706
+3.133414	0.031123	-0.055063	9.832334	0.048230	0.087266	-0.034374
+3.134414	0.033517	-0.014364	9.825152	0.046764	0.087799	-0.035972
+3.135351	0.079003	-0.040699	9.825152	0.046764	0.085668	-0.031975
+3.136395	0.050275	-0.035911	9.827546	0.044100	0.085268	-0.033574
+3.137416	0.014364	-0.026334	9.794030	0.042634	0.086467	-0.035573
+3.138417	0.052669	-0.023940	9.772483	0.045165	0.087533	-0.039303
+3.139414	0.052669	0.004788	9.801212	0.047697	0.089531	-0.037838
+3.140414	0.033517	0.014364	9.803606	0.048096	0.089931	-0.032775
+3.141414	0.040699	-0.009576	9.782060	0.048763	0.089132	-0.032642
+3.142414	0.052669	0.043093	9.767695	0.050095	0.088199	-0.034240
+3.143386	-0.009576	0.045487	9.762907	0.048096	0.088865	-0.034773
+3.144369	-0.009576	0.009576	9.765301	0.046231	0.087933	-0.037704
+3.145353	0.011970	0.007182	9.829940	0.046764	0.087266	-0.041835
+3.146417	0.000000	0.009576	9.817970	0.046364	0.088865	-0.039570
+3.147414	-0.009576	0.000000	9.762907	0.045965	0.088998	-0.037038
+3.148377	0.019152	-0.007182	9.801212	0.045965	0.088599	-0.036239
+3.149412	-0.040699	0.009576	9.817970	0.048230	0.086201	-0.035573
+3.150411	-0.016758	0.007182	9.801212	0.048763	0.087133	-0.035173
+3.151365	0.000000	-0.019152	9.729391	0.047697	0.088998	-0.038637
+3.152414	0.064639	0.016758	9.770089	0.047031	0.088998	-0.036505
+3.153383	0.062245	0.019152	9.853881	0.047430	0.087133	-0.034240
+3.154373	-0.035911	-0.059851	9.772483	0.048896	0.086067	-0.035573
+3.155412	-0.021546	-0.043093	9.798818	0.048363	0.085268	-0.036772
+3.156375	-0.009576	-0.062245	9.837123	0.046364	0.088199	-0.035040
+3.157414	0.002394	-0.011970	9.750937	0.045032	0.088998	-0.037438
+3.158417	-0.011970	-0.040699	9.770089	0.045832	0.088066	-0.040236
+3.159414	-0.009576	-0.052669	9.760513	0.045698	0.088865	-0.037704
+3.160414	-0.007182	-0.009576	9.777271	0.045165	0.090597	-0.036505
+3.161415	0.019152	0.014364	9.834729	0.045698	0.090064	-0.034240
+3.162367	0.031123	-0.004788	9.779666	0.046364	0.086867	-0.033841
+3.163390	0.035911	-0.021546	9.784454	0.045565	0.086867	-0.034907
+3.164366	0.011970	-0.038305	9.810788	0.046498	0.088332	-0.037438
+3.165407	0.026334	-0.028729	9.784454	0.046498	0.089531	-0.038371
+3.166414	0.000000	-0.023940	9.827546	0.046098	0.087000	-0.039436
+3.167412	-0.021546	-0.019152	9.712632	0.047031	0.088599	-0.036772
+3.168373	0.002394	-0.045487	9.815576	0.047697	0.087266	-0.035839
+3.169348	-0.014364	-0.038305	9.794030	0.046897	0.089665	-0.033441
+3.170414	0.007182	-0.031123	9.853881	0.047164	0.089531	-0.038504
+3.171381	0.021546	-0.016758	9.801212	0.045965	0.087933	-0.039303
+3.172367	0.038305	0.028729	9.729391	0.046631	0.087933	-0.037305
+3.173407	-0.004788	-0.007182	9.743755	0.049029	0.089798	-0.037172
+3.174408	-0.019152	0.007182	9.815576	0.048496	0.090331	-0.038637
+3.175412	-0.007182	0.011970	9.885003	0.046231	0.088466	-0.036772
+3.176406	0.021546	-0.026334	9.865851	0.044366	0.086867	-0.033708
+3.177413	0.004788	0.002394	9.801212	0.045565	0.086334	-0.035040
+3.178367	0.050275	-0.019152	9.777271	0.046631	0.087533	-0.033308
+3.179413	0.011970	0.011970	9.827546	0.047697	0.088599	-0.035706
+3.180334	-0.007182	-0.009576	9.810788	0.046498	0.092196	-0.039570
+3.181358	0.038305	-0.016758	9.741361	0.043700	0.088865	-0.036372
+3.182348	0.019152	0.007182	9.789242	0.043833	0.085401	-0.033308
+3.183410	-0.011970	-0.014364	9.849093	0.043300	0.087666	-0.032109
+3.184328	0.040699	0.002394	9.822758	0.046764	0.086867	-0.033574
+3.185329	-0.040699	-0.019152	9.825152	0.047697	0.087000	-0.035972
+3.186320	0.021546	0.002394	9.853881	0.049962	0.088466	-0.034374
+3.187318	0.016758	0.016758	9.762907	0.048629	0.088066	-0.034640
+3.188340	-0.011970	-0.045487	9.777271	0.047963	0.088199	-0.037305
+3.189321	-0.019152	-0.016758	9.798818	0.046498	0.088599	-0.032775
+3.190413	0.009576	-0.019152	9.772483	0.048230	0.088332	-0.031576
+3.191415	0.014364	-0.038305	9.753331	0.048496	0.086600	-0.034374
+3.192351	-0.002394	-0.047881	9.846699	0.048230	0.085534	-0.034107
+3.193354	0.021546	-0.002394	9.806000	0.045299	0.086334	-0.034640
+3.194374	0.028729	0.011970	9.851487	0.046231	0.088332	-0.032508
+3.195353	-0.007182	0.040699	9.808394	0.047031	0.087666	-0.035706
+3.196349	0.004788	0.002394	9.853881	0.046764	0.088332	-0.035173
+3.197348	0.028729	0.004788	9.825152	0.047430	0.088732	-0.035839
+3.198350	0.021546	0.016758	9.849093	0.048096	0.087400	-0.035040
+3.199347	0.028729	0.043093	9.741361	0.047963	0.084602	-0.035440
+3.200342	0.016758	0.011970	9.755725	0.048496	0.087000	-0.034907
+3.201348	0.011970	-0.052669	9.762907	0.048896	0.085135	-0.032642
+3.202339	-0.007182	-0.052669	9.774877	0.046631	0.086067	-0.032508
+3.203313	0.002394	-0.031123	9.729391	0.044766	0.088599	-0.036772
+3.204350	0.000000	-0.033517	9.774877	0.044499	0.090331	-0.041435
+3.205353	-0.038305	-0.011970	9.801212	0.045432	0.090864	-0.037971
+3.206417	0.023940	0.002394	9.841911	0.048629	0.090997	-0.032508
+3.207411	-0.014364	-0.002394	9.829940	0.049562	0.089665	-0.033308
+3.208427	0.038305	0.035911	9.743755	0.049162	0.088199	-0.035972
+3.209415	0.033517	-0.035911	9.750937	0.047963	0.088332	-0.034374
+3.210357	-0.014364	-0.023940	9.738967	0.047297	0.089132	-0.036372
+3.211333	-0.011970	0.021546	9.729391	0.045832	0.088998	-0.038237
+3.212331	0.028729	0.019152	9.755725	0.046498	0.088998	-0.037971
+3.213348	0.004788	-0.040699	9.736573	0.046764	0.087533	-0.035839
+3.214345	0.004788	-0.009576	9.722208	0.046364	0.087400	-0.038104
+3.215328	-0.043093	0.035911	9.777271	0.047031	0.087799	-0.037305
+3.216323	-0.071821	0.009576	9.820364	0.047430	0.088066	-0.039037
+3.217324	-0.009576	0.021546	9.798818	0.045032	0.086334	-0.037172
+3.218322	0.038305	-0.016758	9.786848	0.046764	0.087400	-0.038371
+3.219344	0.011970	-0.016758	9.722208	0.048096	0.088599	-0.039570
+3.220340	-0.023940	-0.023940	9.803606	0.048096	0.088599	-0.035972
+3.221347	0.026334	-0.055063	9.841911	0.046631	0.086867	-0.034240
+3.222361	0.069427	0.014364	9.829940	0.044766	0.087666	-0.036239
+3.223339	-0.004788	-0.074215	9.743755	0.046498	0.089132	-0.038237
+3.224403	0.033517	-0.028729	9.748543	0.047297	0.087266	-0.038637
+3.225354	0.009576	0.000000	9.796424	0.048096	0.084602	-0.035440
+3.226328	-0.052669	-0.021546	9.820364	0.047297	0.084602	-0.034374
+3.227340	-0.035911	-0.009576	9.810788	0.047164	0.087533	-0.038904
+3.228341	0.052669	-0.004788	9.791636	0.049296	0.088199	-0.037305
+3.229341	0.045487	0.016758	9.796424	0.047830	0.089265	-0.034107
+3.230273	0.019152	0.047881	9.808394	0.045832	0.087133	-0.033041
+3.231275	0.038305	0.052669	9.856275	0.047164	0.085934	-0.035839
+3.232281	-0.019152	0.052669	9.889792	0.049296	0.086201	-0.035440
+3.233348	-0.007182	0.009576	9.858669	0.047963	0.089132	-0.038504
+3.234298	-0.052669	-0.069427	9.856275	0.047830	0.088732	-0.035440
+3.235285	0.000000	-0.023940	9.877821	0.046631	0.088199	-0.031975
+3.236354	0.007182	-0.038305	9.798818	0.045698	0.087533	-0.032375
+3.237353	0.031123	0.014364	9.741361	0.044366	0.087933	-0.035173
+3.238310	0.004788	-0.031123	9.755725	0.045965	0.088998	-0.038904
+3.239354	0.000000	-0.045487	9.882609	0.049695	0.089798	-0.036505
+3.240351	0.050275	-0.031123	9.882609	0.047564	0.086600	-0.034773
+3.241353	0.028729	-0.045487	9.920914	0.045832	0.085801	-0.034107
+3.242356	0.040699	-0.023940	9.861063	0.046764	0.086334	-0.036106
+3.243348	0.040699	0.014364	9.774877	0.049429	0.088332	-0.037971
+3.244302	0.011970	0.019152	9.686298	0.048763	0.087799	-0.038504
+3.245351	0.002394	-0.004788	9.755725	0.048763	0.087799	-0.038237
+3.246357	0.016758	-0.040699	9.803606	0.045299	0.088066	-0.036772
+3.247355	-0.011970	-0.040699	9.789242	0.044899	0.088599	-0.035706
+3.248354	-0.031123	-0.033517	9.861063	0.045965	0.086867	-0.040236
+3.249355	-0.028729	-0.014364	9.834729	0.046764	0.087400	-0.039703
+3.250364	-0.002394	-0.033517	9.911338	0.046098	0.089665	-0.036639
+3.251381	-0.021546	0.009576	9.798818	0.045032	0.089798	-0.037305
+3.252382	-0.011970	-0.002394	9.765301	0.044632	0.089931	-0.037571
+3.253351	0.019152	0.000000	9.789242	0.047830	0.089265	-0.036239
+3.254363	0.021546	-0.043093	9.839517	0.050761	0.087666	-0.035839
+3.255371	0.021546	-0.021546	9.798818	0.050228	0.087933	-0.037704
+3.256415	0.002394	-0.040699	9.834729	0.047697	0.089931	-0.039436
+3.257418	0.009576	-0.014364	9.786848	0.044100	0.090464	-0.038504
+3.258345	-0.043093	0.031123	9.729391	0.045165	0.090198	-0.037305
+3.259411	0.004788	0.016758	9.841911	0.045432	0.087400	-0.037838
+3.260353	0.004788	-0.026334	9.806000	0.044899	0.087000	-0.037971
+3.261413	-0.016758	0.009576	9.679116	0.045032	0.082070	-0.034907
+3.262412	-0.021546	-0.004788	9.738967	0.045032	0.084469	-0.036639
+3.263348	0.007182	-0.016758	9.796424	0.046764	0.086734	-0.038504
+3.264415	0.011970	-0.050275	9.844305	0.044766	0.088332	-0.038637
+3.265354	-0.031123	-0.028729	9.849093	0.044766	0.087933	-0.039303
+3.266347	0.011970	-0.019152	9.832334	0.046231	0.087133	-0.041435
+3.267346	-0.019152	0.016758	9.765301	0.047164	0.087400	-0.038371
+3.268326	-0.004788	0.033517	9.693480	0.047697	0.088332	-0.035306
+3.269317	-0.019152	-0.009576	9.765301	0.049296	0.089132	-0.036505
+3.270371	-0.031123	0.002394	9.896974	0.047031	0.086867	-0.037838
+3.271329	0.033517	0.035911	9.798818	0.045565	0.085534	-0.036372
+3.272316	-0.014364	0.014364	9.700662	0.046498	0.086734	-0.033574
+3.273293	-0.004788	0.016758	9.753331	0.044632	0.087266	-0.031576
+3.274343	0.055063	0.062245	9.791636	0.044100	0.087000	-0.036639
+3.275341	0.067033	0.007182	9.782060	0.048763	0.087799	-0.036639
+3.276339	0.009576	0.009576	9.870639	0.051028	0.090730	-0.032642
+3.277339	0.026334	-0.009576	9.813182	0.048363	0.091796	-0.034107
+3.278297	0.052669	0.023940	9.808394	0.047697	0.090597	-0.034107
+3.279293	0.019152	0.035911	9.837123	0.048096	0.090730	-0.035706
+3.280282	0.002394	0.000000	9.877821	0.048363	0.086201	-0.039303
+3.281288	0.021546	0.002394	9.810788	0.048763	0.088066	-0.038371
+3.282286	0.067033	-0.014364	9.832334	0.048230	0.089398	-0.036372
+3.283278	0.011970	0.007182	9.825152	0.046098	0.089265	-0.035573
+3.284276	-0.026334	-0.062245	9.782060	0.045032	0.088066	-0.036239
+3.285276	0.023940	-0.028729	9.841911	0.046231	0.087799	-0.035972
+3.286279	0.011970	-0.011970	9.803606	0.045299	0.087933	-0.035573
+3.287286	0.033517	-0.026334	9.729391	0.046498	0.086067	-0.031975
+3.288284	-0.028729	-0.026334	9.827546	0.050761	0.086467	-0.034374
+3.289294	0.014364	-0.047881	9.820364	0.050095	0.086867	-0.040502
+3.290276	0.050275	-0.021546	9.841911	0.048230	0.086334	-0.039303
+3.291276	0.021546	-0.026334	9.806000	0.049029	0.085801	-0.035306
+3.292274	-0.002394	0.031123	9.770089	0.049429	0.088599	-0.033841
+3.293275	0.031123	-0.007182	9.762907	0.048363	0.090331	-0.039836
+3.294274	-0.069427	0.007182	9.789242	0.046231	0.089265	-0.041835
+3.295291	-0.033517	-0.016758	9.820364	0.043433	0.087400	-0.037438
+3.296289	-0.007182	0.011970	9.798818	0.045432	0.088332	-0.036106
+3.297350	0.002394	0.057457	9.782060	0.049162	0.087933	-0.036772
+3.298353	0.098156	-0.026334	9.825152	0.048096	0.084069	-0.035972
+3.299342	0.088580	0.011970	9.849093	0.046764	0.083403	-0.037704
+3.300294	0.045487	-0.019152	9.808394	0.047430	0.087133	-0.037438
+3.301292	0.059851	0.040699	9.779666	0.045832	0.087400	-0.037704
+3.302379	0.016758	0.016758	9.820364	0.045698	0.087799	-0.037172
+3.303377	-0.009576	0.050275	9.815576	0.048096	0.088066	-0.037438
+3.304342	0.004788	-0.019152	9.774877	0.049695	0.089798	-0.037438
+3.305381	-0.028729	0.045487	9.782060	0.047564	0.085934	-0.034907
+3.306379	0.026334	0.014364	9.753331	0.045698	0.085401	-0.035306
+3.307380	0.004788	-0.011970	9.772483	0.047963	0.086067	-0.037704
+3.308320	0.026334	0.014364	9.873033	0.049562	0.086334	-0.039303
+3.309338	0.011970	-0.021546	9.839517	0.050095	0.086867	-0.037704
+3.310360	0.007182	-0.124490	9.760513	0.049029	0.087799	-0.036106
+3.311379	-0.038305	-0.055063	9.762907	0.048363	0.086734	-0.036772
+3.312319	0.035911	-0.043093	9.806000	0.047031	0.086467	-0.037438
+3.313382	-0.007182	0.002394	9.959219	0.045432	0.086467	-0.038104
+3.314382	-0.002394	-0.009576	9.873033	0.047430	0.087799	-0.037438
+3.315379	-0.009576	0.028729	9.858669	0.048096	0.090464	-0.035972
+3.316321	0.002394	0.004788	9.899368	0.047697	0.089398	-0.034107
+3.317311	0.007182	-0.004788	9.774877	0.045432	0.086600	-0.032642
+3.318304	0.040699	0.033517	9.750937	0.045565	0.085534	-0.033841
+3.319301	0.045487	0.028729	9.753331	0.046364	0.087666	-0.032375
+3.320299	0.064639	-0.009576	9.813182	0.046231	0.088865	-0.033041
+3.321328	0.047881	-0.004788	9.844305	0.047031	0.088066	-0.037305
+3.322341	0.002394	-0.062245	9.755725	0.048496	0.086201	-0.037704
+3.323379	-0.047881	-0.047881	9.803606	0.047430	0.085801	-0.037038
+3.324379	-0.019152	-0.011970	9.901762	0.045032	0.088066	-0.035573
+3.325382	-0.007182	-0.007182	9.865851	0.047697	0.088332	-0.037305
+3.326368	-0.019152	0.016758	9.782060	0.049828	0.087533	-0.038904
+3.327369	-0.031123	-0.011970	9.770089	0.046764	0.090597	-0.039037
+3.328416	-0.016758	-0.004788	9.844305	0.046631	0.089665	-0.034507
+3.329413	-0.086186	-0.009576	9.837123	0.046764	0.088199	-0.034907
+3.330371	-0.019152	0.011970	9.772483	0.043966	0.088732	-0.036106
+3.331373	0.009576	0.007182	9.796424	0.045299	0.086334	-0.035040
+3.332373	-0.009576	0.009576	9.849093	0.047297	0.083802	-0.035173
+3.333337	-0.002394	-0.007182	9.853881	0.048496	0.086201	-0.037571
+3.334335	-0.031123	-0.043093	9.906550	0.047963	0.091130	-0.037038
+3.335339	0.014364	0.000000	9.803606	0.048363	0.089931	-0.035972
+3.336412	-0.009576	0.031123	9.782060	0.048230	0.088199	-0.035440
+3.337413	-0.031123	-0.014364	9.822758	0.048096	0.089398	-0.036239
+3.338413	0.028729	-0.069427	9.774877	0.047031	0.086334	-0.039303
+3.339413	0.023940	-0.040699	9.837123	0.045032	0.085268	-0.041302
+3.340345	0.035911	-0.031123	9.794030	0.045965	0.085135	-0.038104
+3.341409	0.016758	-0.047881	9.777271	0.048096	0.088599	-0.036905
+3.342416	-0.028729	0.023940	9.829940	0.047164	0.090331	-0.037971
+3.343350	-0.016758	0.019152	9.810788	0.046231	0.091130	-0.041035
+3.344412	-0.011970	-0.016758	9.774877	0.046498	0.089132	-0.039037
+3.345358	-0.014364	-0.023940	9.765301	0.045965	0.088732	-0.035706
+3.346415	-0.007182	0.000000	9.760513	0.044632	0.088332	-0.034107
+3.347413	-0.004788	-0.035911	9.827546	0.044100	0.088466	-0.033441
+3.348413	-0.004788	-0.016758	9.832334	0.046498	0.090464	-0.035173
+3.349314	-0.028729	-0.021546	9.827546	0.048896	0.088599	-0.037971
+3.350345	-0.011970	-0.007182	9.767695	0.047963	0.085668	-0.036905
+3.351370	0.035911	-0.050275	9.746149	0.047564	0.083669	-0.035040
+3.352412	0.016758	-0.004788	9.748543	0.046631	0.089132	-0.036239
+3.353410	0.035911	0.050275	9.791636	0.047430	0.090464	-0.036106
+3.354375	-0.004788	-0.007182	9.825152	0.048230	0.086734	-0.037971
+3.355412	0.033517	-0.021546	9.772483	0.047830	0.085934	-0.034374
+3.356414	-0.004788	-0.038305	9.798818	0.045565	0.088466	-0.033441
+3.357411	0.052669	-0.055063	9.806000	0.043567	0.088332	-0.033574
+3.358343	0.069427	-0.026334	9.774877	0.044233	0.085002	-0.036772
+3.359380	0.016758	-0.014364	9.808394	0.044766	0.086067	-0.037172
+3.360414	0.019152	-0.004788	9.777271	0.047564	0.086334	-0.038104
+3.361413	0.033517	-0.002394	9.806000	0.047430	0.085534	-0.041968
+3.362414	0.016758	0.031123	9.858669	0.047697	0.087266	-0.040369
+3.363413	-0.035911	-0.031123	9.786848	0.046498	0.088865	-0.034640
+3.364412	-0.026334	-0.021546	9.820364	0.048230	0.087133	-0.036239
+3.365411	0.002394	0.002394	9.786848	0.047697	0.088998	-0.035306
+3.366413	0.019152	0.023940	9.743755	0.047963	0.087799	-0.034374
+3.367353	0.057457	0.023940	9.753331	0.045832	0.089398	-0.037172
+3.368349	-0.019152	-0.059851	9.734179	0.046098	0.090730	-0.037704
+3.369301	0.028729	-0.047881	9.894580	0.045432	0.088332	-0.032908
+3.370331	0.055063	-0.014364	9.846699	0.045165	0.089398	-0.029711
+3.371305	0.033517	-0.023940	9.726997	0.044499	0.089531	-0.031709
+3.372323	0.023940	-0.014364	9.801212	0.043167	0.086600	-0.034374
+3.373411	0.007182	0.002394	9.813182	0.047697	0.086734	-0.037438
+3.374417	0.033517	-0.043093	9.782060	0.045965	0.088066	-0.035573
+3.375365	0.045487	-0.026334	9.750937	0.046098	0.089398	-0.033175
+3.376336	0.000000	0.009576	9.753331	0.047697	0.087266	-0.032908
+3.377369	-0.014364	0.031123	9.719814	0.048896	0.085668	-0.036372
+3.378320	0.043093	0.000000	9.736573	0.046764	0.087133	-0.037704
+3.379344	0.052669	-0.009576	9.794030	0.045432	0.086600	-0.037038
+3.380325	0.038305	-0.040699	9.794030	0.047430	0.088599	-0.035706
+3.381341	0.038305	-0.019152	9.810788	0.047963	0.086600	-0.031443
+3.382342	0.028729	-0.040699	9.779666	0.046498	0.087799	-0.031443
+3.383339	0.011970	-0.052669	9.796424	0.045965	0.088066	-0.036772
+3.384339	0.019152	0.021546	9.846699	0.045565	0.088332	-0.039170
+3.385345	-0.014364	0.009576	9.868245	0.046897	0.089798	-0.036106
+3.386357	-0.009576	-0.016758	9.772483	0.047697	0.091263	-0.032242
+3.387355	-0.004788	-0.026334	9.782060	0.046764	0.086867	-0.034507
+3.388358	-0.004788	-0.007182	9.738967	0.047164	0.085668	-0.035306
+3.389312	0.007182	0.014364	9.679116	0.048896	0.087133	-0.034507
+3.390297	-0.019152	0.021546	9.722208	0.048496	0.086201	-0.035706
+3.391300	-0.019152	0.002394	9.806000	0.046498	0.087799	-0.036239
+3.392291	0.021546	0.057457	9.849093	0.046098	0.090331	-0.037305
+3.393273	0.026334	-0.019152	9.817970	0.046498	0.090198	-0.035040
+3.394273	0.045487	0.002394	9.861063	0.045299	0.088199	-0.033574
+3.395301	0.038305	0.028729	9.748543	0.042767	0.088199	-0.034507
+3.396291	0.031123	0.021546	9.758119	0.046231	0.087133	-0.035440
+3.397291	-0.002394	-0.035911	9.832334	0.049296	0.087799	-0.035706
+3.398286	0.004788	-0.035911	9.791636	0.047830	0.086600	-0.037704
+3.399310	0.009576	-0.047881	9.789242	0.044499	0.087666	-0.038637
+3.400312	0.043093	-0.067033	9.894580	0.044366	0.088599	-0.040769
+3.401302	0.021546	-0.028729	9.808394	0.048096	0.086201	-0.038371
+3.402331	0.019152	-0.004788	9.820364	0.046364	0.085135	-0.037438
+3.403341	0.021546	-0.040699	9.844305	0.046364	0.086600	-0.035440
+3.404338	0.050275	0.026334	9.834729	0.046897	0.089798	-0.035839
+3.405421	0.028729	-0.011970	9.738967	0.050361	0.088332	-0.037571
+3.406413	-0.014364	-0.047881	9.784454	0.051161	0.085135	-0.037305
+3.407412	-0.057457	-0.016758	9.861063	0.050095	0.085934	-0.034107
+3.408410	0.004788	-0.028729	9.892186	0.049162	0.086867	-0.033574
+3.409410	0.076609	0.023940	9.880215	0.047697	0.086467	-0.036772
+3.410354	0.067033	-0.009576	9.765301	0.045698	0.086334	-0.036372
+3.411364	0.023940	-0.052669	9.726997	0.045965	0.087533	-0.034374
+3.412329	-0.038305	-0.004788	9.765301	0.047164	0.087533	-0.035040
+3.413411	-0.028729	-0.050275	9.774877	0.047963	0.087400	-0.035839
+3.414371	0.021546	-0.083792	9.770089	0.045565	0.085401	-0.034907
+3.415411	0.011970	-0.019152	9.861063	0.045165	0.085801	-0.038904
+3.416410	0.031123	0.002394	9.887397	0.047297	0.088732	-0.038237
+3.417412	0.035911	0.016758	9.820364	0.049962	0.089265	-0.037172
+3.418353	0.000000	0.007182	9.873033	0.048096	0.088865	-0.035440
+3.419325	0.021546	0.000000	9.829940	0.045299	0.086734	-0.036106
+3.420396	0.057457	-0.035911	9.887397	0.045965	0.086067	-0.033175
+3.421341	0.045487	-0.002394	9.841911	0.048896	0.088199	-0.032109
+3.422414	0.035911	-0.019152	9.806000	0.047963	0.088199	-0.034507
+3.423365	0.045487	-0.002394	9.798818	0.049029	0.087799	-0.036106
+3.424410	0.009576	-0.014364	9.827546	0.048496	0.088332	-0.035839
+3.425369	0.026334	0.043093	9.858669	0.044899	0.089798	-0.034240
+3.426415	0.011970	0.090974	9.901762	0.045032	0.089665	-0.037704
+3.427410	0.007182	0.081397	9.913732	0.045032	0.086734	-0.037172
+3.428409	0.011970	0.050275	9.892186	0.044499	0.086600	-0.036505
+3.429411	0.019152	-0.021546	9.791636	0.044366	0.086734	-0.037971
+3.430348	-0.035911	-0.028729	9.813182	0.048363	0.086334	-0.038770
+3.431409	0.016758	-0.050275	9.784454	0.048896	0.085934	-0.037038
+3.432412	0.002394	0.002394	9.717420	0.046364	0.088599	-0.037571
+3.433413	0.050275	-0.035911	9.719814	0.045032	0.088865	-0.033974
+3.434348	0.019152	-0.079003	9.731785	0.045432	0.088466	-0.034507
+3.435353	-0.007182	-0.004788	9.695874	0.046098	0.086201	-0.037838
+3.436411	0.000000	0.023940	9.808394	0.047830	0.084602	-0.037971
+3.437379	-0.009576	0.031123	9.829940	0.048363	0.088332	-0.035440
+3.438411	-0.004788	0.004788	9.806000	0.047430	0.091130	-0.037704
+3.439343	0.019152	-0.011970	9.784454	0.047031	0.089931	-0.037438
+3.440286	0.052669	-0.035911	9.770089	0.046364	0.088466	-0.038637
+3.441312	0.019152	-0.023940	9.834729	0.045965	0.087666	-0.036772
+3.442318	0.014364	-0.035911	9.801212	0.045432	0.089132	-0.035040
+3.443412	0.052669	-0.055063	9.748543	0.046231	0.085135	-0.038371
+3.444410	0.021546	-0.052669	9.671934	0.046897	0.084602	-0.037438
+3.445343	0.021546	0.016758	9.758119	0.045565	0.087533	-0.036239
+3.446413	0.028729	0.019152	9.806000	0.044766	0.087933	-0.036505
+3.447410	0.026334	0.002394	9.722208	0.045299	0.087666	-0.038371
+3.448410	-0.021546	-0.031123	9.707844	0.046498	0.084868	-0.039836
+3.449350	-0.016758	-0.040699	9.801212	0.047430	0.086067	-0.035173
+3.450348	-0.028729	-0.040699	9.791636	0.049162	0.087266	-0.033974
+3.451346	-0.035911	-0.050275	9.803606	0.049029	0.087933	-0.033974
+3.452358	0.004788	-0.038305	9.750937	0.047430	0.087266	-0.034507
+3.453412	0.002394	-0.021546	9.703056	0.049029	0.087799	-0.036106
+3.454398	-0.035911	-0.031123	9.782060	0.047564	0.087933	-0.036372
+3.455411	0.009576	-0.016758	9.734179	0.047564	0.090331	-0.037438
+3.456410	0.079003	-0.023940	9.750937	0.045698	0.092995	-0.037438
+3.457412	0.038305	0.009576	9.808394	0.045698	0.092596	-0.037704
+3.458413	0.031123	-0.021546	9.865851	0.046231	0.090064	-0.036772
+3.459345	0.016758	-0.031123	9.801212	0.047830	0.087533	-0.033441
+3.460411	0.007182	0.095762	9.762907	0.048763	0.086600	-0.036772
+3.461412	-0.004788	0.052669	9.806000	0.045565	0.085401	-0.037438
+3.462416	0.016758	0.004788	9.794030	0.045432	0.088599	-0.037172
+3.463411	0.009576	0.011970	9.813182	0.046764	0.090730	-0.037172
+3.464410	-0.026334	0.019152	9.806000	0.047697	0.090064	-0.037305
+3.465368	-0.026334	-0.004788	9.791636	0.048096	0.090198	-0.036905
+3.466410	0.035911	0.011970	9.796424	0.047963	0.089398	-0.037571
+3.467349	0.014364	-0.004788	9.803606	0.046897	0.087533	-0.036372
+3.468324	-0.059851	0.016758	9.710238	0.046498	0.085934	-0.035173
+3.469374	-0.057457	-0.021546	9.703056	0.049296	0.087000	-0.035306
+3.470329	-0.004788	-0.019152	9.803606	0.047564	0.086734	-0.036106
+3.471346	-0.021546	-0.062245	9.803606	0.045165	0.085268	-0.035306
+3.472345	-0.002394	-0.040699	9.789242	0.044366	0.087133	-0.034907
+3.473346	-0.004788	-0.038305	9.789242	0.044499	0.086600	-0.038770
+3.474363	-0.004788	-0.002394	9.813182	0.047031	0.086734	-0.038770
+3.475408	0.021546	-0.040699	9.829940	0.048496	0.085668	-0.041302
+3.476349	0.019152	0.011970	9.803606	0.048096	0.089398	-0.038237
+3.477412	0.004788	-0.040699	9.779666	0.047164	0.090464	-0.033708
+3.478366	0.047881	-0.019152	9.844305	0.049429	0.087400	-0.033041
+3.479403	0.009576	0.019152	9.820364	0.049562	0.087133	-0.036772
+3.480371	0.043093	-0.002394	9.798818	0.046897	0.089132	-0.041035
+3.481348	0.026334	-0.033517	9.710238	0.045565	0.085668	-0.039836
+3.482344	0.004788	-0.021546	9.705450	0.047830	0.084602	-0.037571
+3.483409	0.009576	-0.004788	9.741361	0.048496	0.086734	-0.036372
+3.484326	0.045487	-0.045487	9.755725	0.048896	0.087799	-0.036772
+3.485321	0.035911	-0.067033	9.762907	0.049029	0.086734	-0.039969
+3.486342	-0.040699	-0.021546	9.849093	0.047830	0.089531	-0.037438
+3.487340	-0.059851	-0.004788	9.774877	0.046764	0.087266	-0.033308
+3.488341	0.016758	-0.016758	9.738967	0.049162	0.085135	-0.036239
+3.489337	0.021546	0.002394	9.873033	0.045832	0.086467	-0.036905
+3.490340	-0.016758	0.023940	9.755725	0.043300	0.086201	-0.034507
+3.491338	-0.035911	0.019152	9.777271	0.045565	0.085934	-0.033974
+3.492337	0.011970	-0.026334	9.770089	0.045432	0.087133	-0.034107
+3.493347	0.026334	-0.011970	9.822758	0.044632	0.087266	-0.036772
+3.494370	-0.007182	-0.040699	9.829940	0.045965	0.087400	-0.037838
+3.495411	0.026334	-0.064639	9.777271	0.048629	0.090464	-0.034374
+3.496413	0.016758	-0.038305	9.810788	0.047830	0.088998	-0.032775
+3.497415	-0.014364	-0.009576	9.798818	0.045832	0.088865	-0.033175
+3.498410	0.035911	0.019152	9.887397	0.045432	0.090597	-0.035972
+3.499366	0.079003	-0.016758	9.863457	0.043966	0.089132	-0.032508
+3.500407	0.038305	0.004788	9.806000	0.047031	0.089398	-0.034907
+3.501408	0.004788	-0.009576	9.796424	0.049562	0.087666	-0.036106
+3.502343	-0.011970	-0.062245	9.846699	0.048763	0.084735	-0.035040
+3.503403	0.026334	-0.083792	9.801212	0.048096	0.086334	-0.035440
+3.504401	0.050275	-0.076609	9.738967	0.046231	0.087533	-0.035440
+3.505404	0.026334	0.026334	9.801212	0.047963	0.087533	-0.032109
+3.506405	0.045487	0.038305	9.829940	0.046764	0.085534	-0.033041
+3.507403	0.038305	0.014364	9.789242	0.045299	0.088332	-0.037704
+3.508376	0.059851	0.023940	9.777271	0.045698	0.090864	-0.034640
+3.509398	0.019152	0.031123	9.782060	0.046231	0.088998	-0.033574
+3.510329	0.026334	-0.026334	9.753331	0.047430	0.086067	-0.034107
+3.511333	0.050275	-0.045487	9.873033	0.045965	0.088066	-0.039037
+3.512324	0.047881	0.019152	9.837123	0.046631	0.087400	-0.039436
+3.513408	0.035911	0.043093	9.885003	0.047963	0.086734	-0.039836
+3.514333	0.038305	-0.014364	9.880215	0.046364	0.087533	-0.037704
+3.515322	0.002394	-0.038305	9.741361	0.043966	0.084602	-0.037038
+3.516326	0.021546	0.002394	9.758119	0.044499	0.083802	-0.035839
+3.517342	0.009576	0.047881	9.868245	0.044899	0.086467	-0.033841
+3.518315	0.014364	0.011970	9.837123	0.044766	0.090597	-0.033308
+3.519403	0.026334	0.009576	9.832334	0.047430	0.088998	-0.035173
+3.520304	-0.045487	0.047881	9.880215	0.049296	0.088332	-0.039570
+3.521299	-0.014364	-0.040699	9.794030	0.047564	0.089931	-0.038770
+3.522319	-0.004788	-0.023940	9.738967	0.045965	0.091130	-0.039037
+3.523311	0.002394	0.033517	9.801212	0.045032	0.090198	-0.036505
+3.524300	0.040699	0.047881	9.832334	0.044899	0.088199	-0.036372
+3.525341	0.043093	0.043093	9.813182	0.047830	0.089531	-0.036905
+3.526337	0.062245	0.019152	9.817970	0.047297	0.086867	-0.034240
+3.527337	0.064639	0.026334	9.913732	0.047430	0.089931	-0.035040
+3.528343	-0.038305	-0.009576	9.813182	0.047164	0.091663	-0.037438
+3.529306	0.007182	-0.019152	9.724603	0.047963	0.088066	-0.038637
+3.530269	-0.002394	0.035911	9.767695	0.049828	0.085668	-0.034907
+3.531278	0.040699	0.000000	9.798818	0.047697	0.087266	-0.037704
+3.532301	-0.007182	0.031123	9.794030	0.044233	0.087000	-0.037704
+3.533299	-0.009576	0.016758	9.815576	0.044766	0.086600	-0.036372
+3.534274	0.045487	0.011970	9.782060	0.046631	0.086467	-0.037172
+3.535283	0.026334	-0.004788	9.841911	0.047031	0.088998	-0.038904
+3.536300	0.035911	-0.011970	9.870639	0.045698	0.088865	-0.037571
+3.537349	0.019152	0.019152	9.851487	0.044632	0.087000	-0.037438
+3.538345	0.007182	0.004788	9.770089	0.044766	0.085668	-0.038371
+3.539354	0.000000	-0.009576	9.825152	0.046364	0.086334	-0.036772
+3.540350	0.016758	-0.007182	9.882609	0.047297	0.090198	-0.034240
+3.541342	0.052669	-0.033517	9.808394	0.047164	0.090730	-0.034640
+3.542347	0.026334	0.016758	9.777271	0.047697	0.087533	-0.037438
+3.543350	-0.028729	-0.033517	9.750937	0.048496	0.087933	-0.039170
+3.544285	0.021546	-0.038305	9.880215	0.048230	0.088865	-0.035573
+3.545352	0.035911	0.023940	9.827546	0.046364	0.085668	-0.037704
+3.546340	0.038305	0.014364	9.822758	0.045032	0.086334	-0.037172
+3.547303	0.019152	0.002394	9.762907	0.047963	0.088998	-0.034907
+3.548349	-0.007182	-0.045487	9.794030	0.047297	0.089931	-0.033841
+3.549283	-0.007182	-0.055063	9.746149	0.044499	0.088599	-0.035440
+3.550351	-0.004788	-0.038305	9.801212	0.046498	0.086067	-0.036106
+3.551286	0.052669	0.011970	9.772483	0.045832	0.085002	-0.035839
+3.552332	-0.002394	-0.016758	9.796424	0.045965	0.084735	-0.034507
+3.553301	0.035911	0.000000	9.858669	0.046098	0.085135	-0.037172
+3.554310	0.009576	-0.059851	9.863457	0.046764	0.085801	-0.036106
+3.555345	0.004788	-0.055063	9.865851	0.046498	0.088599	-0.035573
+3.556346	-0.014364	-0.031123	9.803606	0.048896	0.090997	-0.035040
+3.557348	0.038305	-0.033517	9.767695	0.047430	0.087533	-0.032908
+3.558351	-0.019152	-0.033517	9.801212	0.045432	0.085668	-0.032775
+3.559307	-0.031123	0.000000	9.806000	0.047830	0.087266	-0.034507
+3.560290	0.011970	-0.019152	9.738967	0.049962	0.087533	-0.033841
+3.561349	-0.014364	-0.031123	9.806000	0.048096	0.088998	-0.038371
+3.562327	-0.004788	-0.002394	9.803606	0.045432	0.089531	-0.039969
+3.563306	0.055063	0.009576	9.873033	0.047697	0.090331	-0.036639
+3.564309	0.007182	0.007182	9.858669	0.045965	0.090864	-0.033308
+3.565350	0.016758	0.016758	9.815576	0.046364	0.089665	-0.033308
+3.566351	-0.011970	-0.007182	9.801212	0.045832	0.088466	-0.034507
+3.567348	-0.076609	0.000000	9.841911	0.043300	0.088199	-0.034640
+3.568388	-0.055063	-0.019152	9.741361	0.045165	0.086600	-0.036905
+3.569349	-0.014364	0.009576	9.762907	0.048763	0.087400	-0.036505
+3.570349	-0.011970	-0.009576	9.770089	0.047430	0.086467	-0.036106
+3.571349	-0.004788	-0.067033	9.815576	0.047031	0.086201	-0.037172
+3.572344	0.047881	-0.045487	9.865851	0.046631	0.087000	-0.036639
+3.573307	0.031123	0.004788	9.786848	0.046631	0.087000	-0.035306
+3.574369	0.021546	-0.016758	9.858669	0.047963	0.088199	-0.034374
+3.575349	0.045487	-0.052669	9.806000	0.046498	0.088066	-0.039037
+3.576351	0.043093	-0.038305	9.885003	0.048230	0.090064	-0.038637
+3.577352	-0.004788	-0.074215	9.868245	0.051028	0.089398	-0.035173
+3.578351	-0.002394	-0.052669	9.803606	0.050228	0.086467	-0.036639
+3.579349	0.059851	-0.050275	9.825152	0.044899	0.087400	-0.035706
+3.580350	0.026334	-0.019152	9.753331	0.044899	0.090864	-0.033574
+3.581351	0.011970	-0.009576	9.837123	0.047430	0.090997	-0.031443
+3.582348	0.067033	0.038305	9.762907	0.047564	0.085135	-0.032642
+3.583318	-0.028729	-0.011970	9.810788	0.047297	0.083669	-0.037305
+3.584347	-0.009576	0.000000	9.794030	0.047430	0.085401	-0.039969
+3.585350	0.019152	0.019152	9.770089	0.048629	0.085668	-0.039037
+3.586352	0.035911	0.011970	9.717420	0.049962	0.084469	-0.038637
+3.587349	0.026334	-0.016758	9.789242	0.047031	0.084469	-0.037438
+3.588350	0.028729	-0.014364	9.798818	0.043300	0.087533	-0.037704
+3.589351	0.019152	-0.052669	9.791636	0.047164	0.087799	-0.036106
+3.590344	0.067033	-0.009576	9.789242	0.046631	0.086600	-0.037438
+3.591349	0.045487	-0.047881	9.813182	0.044899	0.088199	-0.039170
+3.592332	0.019152	-0.062245	9.794030	0.044366	0.090198	-0.037438
+3.593352	0.023940	-0.028729	9.825152	0.045565	0.088732	-0.039170
+3.594330	0.043093	-0.038305	9.865851	0.046364	0.087133	-0.038637
+3.595349	0.016758	-0.004788	9.870639	0.046098	0.086734	-0.035839
+3.596351	-0.011970	0.007182	9.789242	0.045565	0.085401	-0.035706
+3.597351	-0.040699	-0.045487	9.748543	0.043167	0.085002	-0.035839
+3.598352	0.002394	-0.019152	9.798818	0.044233	0.088332	-0.035173
+3.599349	-0.002394	-0.050275	9.748543	0.047963	0.089931	-0.034907
+3.600351	-0.002394	-0.019152	9.782060	0.046498	0.089265	-0.034907
+3.601350	0.002394	-0.033517	9.794030	0.047697	0.088599	-0.036239
+3.602343	-0.026334	-0.004788	9.822758	0.046764	0.089931	-0.038237
+3.603317	0.004788	0.023940	9.782060	0.044632	0.087799	-0.037038
+3.604336	-0.009576	0.021546	9.801212	0.046764	0.086334	-0.035440
+3.605317	0.002394	0.040699	9.758119	0.048096	0.087133	-0.033574
+3.606337	0.000000	0.028729	9.846699	0.046897	0.089531	-0.033441
+3.607335	-0.002394	0.007182	9.789242	0.046231	0.088066	-0.033574
+3.608336	0.033517	-0.007182	9.832334	0.046631	0.087266	-0.035173
+3.609340	0.019152	-0.062245	9.865851	0.047830	0.086867	-0.034507
+3.610346	0.000000	-0.067033	9.815576	0.046231	0.084469	-0.035040
+3.611407	-0.050275	0.019152	9.765301	0.045965	0.085801	-0.037704
+3.612357	-0.038305	0.019152	9.791636	0.044632	0.088865	-0.037172
+3.613357	-0.019152	-0.016758	9.806000	0.045032	0.089265	-0.034240
+3.614367	0.009576	0.028729	9.820364	0.047697	0.086867	-0.036772
+3.615352	-0.011970	-0.026334	9.798818	0.048363	0.087533	-0.038371
+3.616315	-0.002394	-0.052669	9.734179	0.046897	0.086867	-0.035706
+3.617313	-0.007182	-0.038305	9.789242	0.047297	0.087799	-0.034240
+3.618333	0.002394	-0.059851	9.789242	0.049029	0.087666	-0.036505
+3.619323	0.002394	-0.009576	9.767695	0.050628	0.087666	-0.039037
+3.620352	-0.045487	0.016758	9.698268	0.048629	0.089398	-0.039703
+3.621410	-0.014364	-0.019152	9.813182	0.047430	0.089398	-0.037971
+3.622420	0.021546	-0.050275	9.861063	0.047031	0.086334	-0.035706
+3.623347	-0.002394	-0.033517	9.798818	0.046897	0.086067	-0.037838
+3.624364	-0.069427	-0.023940	9.777271	0.048096	0.088998	-0.039703
+3.625350	-0.035911	0.002394	9.746149	0.048496	0.089931	-0.035040
+3.626348	0.026334	0.040699	9.798818	0.047297	0.088466	-0.036505
+3.627343	0.052669	-0.028729	9.808394	0.046631	0.086201	-0.036772
+3.628409	0.023940	0.014364	9.767695	0.046631	0.085002	-0.036106
+3.629409	0.014364	0.016758	9.750937	0.045032	0.087266	-0.037172
+3.630410	0.009576	-0.009576	9.767695	0.045165	0.087133	-0.036372
+3.631414	0.002394	-0.019152	9.736573	0.045832	0.088599	-0.035306
+3.632367	-0.035911	-0.019152	9.791636	0.047164	0.087666	-0.034773
+3.633407	-0.016758	-0.016758	9.856275	0.047963	0.087133	-0.035972
+3.634412	0.011970	-0.019152	9.832334	0.047297	0.087666	-0.036639
+3.635334	0.062245	0.009576	9.760513	0.047297	0.088066	-0.038504
+3.636350	0.057457	0.023940	9.719814	0.046231	0.084335	-0.038637
+3.637348	0.059851	-0.019152	9.748543	0.046231	0.085801	-0.037438
+3.638411	-0.007182	-0.004788	9.815576	0.048230	0.086867	-0.039303
+3.639408	-0.057457	0.011970	9.904156	0.049695	0.086201	-0.035839
+3.640407	-0.004788	-0.023940	9.885003	0.048496	0.088998	-0.037838
+3.641368	0.019152	-0.076609	9.786848	0.047564	0.087799	-0.040636
+3.642370	0.035911	-0.026334	9.738967	0.047430	0.088066	-0.039170
+3.643410	0.043093	-0.011970	9.791636	0.047031	0.088199	-0.038770
+3.644346	0.047881	0.011970	9.729391	0.045698	0.088199	-0.035573
+3.645408	0.067033	-0.016758	9.796424	0.047830	0.088066	-0.038371
+3.646412	0.057457	-0.031123	9.712632	0.046897	0.085934	-0.038237
+3.647409	0.035911	-0.021546	9.820364	0.047697	0.085934	-0.036106
+3.648410	0.055063	-0.040699	9.779666	0.048363	0.085534	-0.036372
+3.649410	0.045487	-0.016758	9.791636	0.049162	0.086600	-0.036239
+3.650364	0.062245	0.038305	9.794030	0.050095	0.086867	-0.035040
+3.651325	0.019152	-0.004788	9.738967	0.046364	0.088066	-0.034240
+3.652424	0.028729	0.062245	9.798818	0.044766	0.088732	-0.034240
+3.653408	-0.028729	-0.004788	9.777271	0.045032	0.088732	-0.033708
+3.654412	0.011970	-0.062245	9.772483	0.046231	0.088066	-0.037438
+3.655410	-0.028729	0.038305	9.734179	0.046364	0.087266	-0.035706
+3.656408	0.016758	0.019152	9.738967	0.047963	0.087000	-0.033175
+3.657410	-0.009576	-0.062245	9.839517	0.046498	0.088466	-0.035173
+3.658409	0.043093	-0.067033	9.786848	0.045299	0.086867	-0.039170
+3.659364	0.059851	0.028729	9.743755	0.043034	0.084868	-0.039969
+3.660400	0.047881	-0.021546	9.686298	0.044100	0.086867	-0.036905
+3.661365	0.045487	-0.019152	9.779666	0.046631	0.086334	-0.039836
+3.662346	0.031123	-0.026334	9.796424	0.049162	0.087400	-0.039836
+3.663316	0.014364	0.011970	9.839517	0.048896	0.088199	-0.034240
+3.664314	-0.002394	-0.019152	9.901762	0.047963	0.088332	-0.034640
+3.665410	-0.033517	0.014364	9.834729	0.046498	0.088466	-0.036772
+3.666410	0.007182	-0.004788	9.798818	0.044366	0.088998	-0.038770
+3.667406	-0.016758	-0.021546	9.791636	0.045432	0.085934	-0.037971
+3.668340	0.014364	-0.043093	9.827546	0.046498	0.086867	-0.037038
+3.669340	0.023940	-0.035911	9.846699	0.045299	0.088732	-0.034240
+3.670361	0.052669	-0.040699	9.837123	0.043966	0.087799	-0.035040
+3.671408	0.045487	-0.019152	9.803606	0.043833	0.086201	-0.034773
+3.672406	0.050275	-0.007182	9.746149	0.047430	0.084735	-0.033708
+3.673407	0.033517	-0.045487	9.810788	0.048230	0.087000	-0.036772
+3.674367	0.043093	-0.011970	9.806000	0.045832	0.090730	-0.036505
+3.675407	0.023940	0.071821	9.794030	0.044366	0.092196	-0.036239
+3.676407	0.026334	-0.028729	9.796424	0.045032	0.090198	-0.037571
+3.677409	0.090974	-0.035911	9.820364	0.045432	0.088332	-0.038237
+3.678350	0.026334	-0.016758	9.913732	0.047297	0.086867	-0.036505
+3.679408	-0.038305	-0.021546	9.889792	0.046897	0.086334	-0.034374
+3.680408	-0.021546	0.011970	9.858669	0.050761	0.087799	-0.035573
+3.681334	0.043093	-0.021546	9.887397	0.050495	0.087933	-0.036505
+3.682411	0.040699	-0.016758	9.798818	0.047963	0.087533	-0.034907
+3.683363	-0.007182	-0.057457	9.810788	0.046364	0.087133	-0.033974
+3.684342	0.009576	-0.004788	9.738967	0.044499	0.088865	-0.035972
+3.685366	0.052669	0.026334	9.794030	0.046231	0.090730	-0.038770
+3.686407	-0.007182	-0.011970	9.837123	0.043167	0.089931	-0.038104
+3.687350	-0.047881	0.002394	9.868245	0.043300	0.086334	-0.037038
+3.688394	0.033517	0.067033	9.801212	0.045299	0.085135	-0.035706
+3.689339	0.009576	-0.002394	9.772483	0.045432	0.084602	-0.036772
+3.690411	-0.011970	0.016758	9.849093	0.045832	0.088199	-0.036905
+3.691407	-0.019152	-0.007182	9.839517	0.045565	0.086734	-0.035306
+3.692402	-0.019152	-0.014364	9.837123	0.045832	0.088865	-0.033974
+3.693340	-0.047881	0.011970	9.925702	0.048496	0.088599	-0.034773
+3.694335	0.028729	0.009576	9.935278	0.048230	0.086867	-0.041035
+3.695334	-0.011970	0.057457	9.887397	0.044499	0.086734	-0.039436
+3.696334	0.019152	-0.011970	9.923308	0.044233	0.089931	-0.036905
+3.697336	0.002394	-0.019152	9.846699	0.045832	0.089931	-0.033841
+3.698264	-0.021546	0.021546	9.791636	0.047297	0.088466	-0.031709
+3.699271	-0.004788	0.016758	9.801212	0.048496	0.088466	-0.032375
+3.700269	0.014364	-0.011970	9.834729	0.046498	0.086467	-0.033175
+3.701353	0.019152	0.011970	9.770089	0.047164	0.084335	-0.035440
+3.702351	0.028729	0.062245	9.767695	0.049296	0.085934	-0.036639
+3.703311	0.043093	0.023940	9.825152	0.046631	0.089132	-0.038904
+3.704291	0.055063	-0.028729	9.815576	0.045698	0.087000	-0.036239
+3.705305	0.026334	0.014364	9.863457	0.048763	0.086867	-0.038637
+3.706350	-0.002394	-0.026334	9.846699	0.048363	0.087799	-0.035573
+3.707348	-0.023940	-0.040699	9.918520	0.047697	0.088066	-0.033441
+3.708348	-0.040699	-0.026334	9.875427	0.046631	0.086600	-0.036372
+3.709333	0.019152	-0.009576	9.774877	0.046098	0.086867	-0.036106
+3.710302	0.023940	0.014364	9.784454	0.047031	0.086600	-0.037305
+3.711346	0.016758	0.031123	9.844305	0.048096	0.086467	-0.037172
+3.712344	0.035911	0.067033	9.870639	0.045565	0.086734	-0.033441
+3.713331	0.011970	-0.004788	9.794030	0.045698	0.086467	-0.035839
+3.714345	0.033517	-0.031123	9.844305	0.045965	0.087000	-0.037305
+3.715336	0.026334	0.026334	9.806000	0.046897	0.088332	-0.039436
+3.716407	0.000000	-0.009576	9.784454	0.048629	0.090597	-0.041701
+3.717405	-0.016758	-0.038305	9.825152	0.050761	0.089132	-0.036505
+3.718369	0.031123	-0.033517	9.873033	0.049695	0.089398	-0.033441
+3.719343	0.043093	-0.019152	9.817970	0.049029	0.089132	-0.034907
+3.720344	0.014364	-0.031123	9.837123	0.044766	0.088332	-0.037172
+3.721344	-0.021546	-0.043093	9.896974	0.044632	0.085401	-0.039170
+3.722343	-0.035911	-0.009576	9.889792	0.045032	0.084202	-0.041435
+3.723342	0.019152	0.035911	9.863457	0.047031	0.084469	-0.035972
+3.724341	0.040699	-0.002394	9.882609	0.047564	0.087533	-0.033974
+3.725343	-0.002394	-0.007182	9.858669	0.045698	0.089398	-0.037172
+3.726342	0.004788	-0.033517	9.837123	0.045432	0.088466	-0.036905
+3.727342	0.019152	-0.040699	9.865851	0.046098	0.086734	-0.034907
+3.728342	0.004788	-0.043093	9.839517	0.047297	0.087266	-0.037571
+3.729343	0.014364	0.011970	9.798818	0.045832	0.087799	-0.036772
+3.730340	0.021546	0.038305	9.772483	0.046498	0.087000	-0.038504
+3.731332	-0.002394	0.000000	9.782060	0.049029	0.086334	-0.037838
+3.732342	0.026334	-0.016758	9.789242	0.048896	0.091130	-0.036772
+3.733341	0.057457	-0.107732	9.825152	0.046231	0.092596	-0.037704
+3.734343	0.026334	-0.057457	9.856275	0.046364	0.089132	-0.036505
+3.735332	-0.019152	-0.014364	9.834729	0.046231	0.086600	-0.039037
+3.736340	0.009576	-0.002394	9.755725	0.045432	0.087533	-0.040236
+3.737408	-0.050275	0.000000	9.772483	0.047031	0.089931	-0.037704
+3.738364	0.021546	0.016758	9.767695	0.047430	0.089132	-0.035839
+3.739358	0.045487	0.038305	9.719814	0.045032	0.087133	-0.037838
+3.740363	-0.011970	0.019152	9.738967	0.045032	0.088865	-0.037438
+3.741402	-0.031123	-0.035911	9.724603	0.046897	0.090730	-0.033574
+3.742408	0.011970	-0.028729	9.779666	0.047963	0.088732	-0.028778
+3.743410	0.021546	0.002394	9.779666	0.049695	0.085534	-0.033175
+3.744407	0.026334	0.021546	9.777271	0.049162	0.088066	-0.037838
+3.745366	0.035911	0.031123	9.791636	0.045965	0.086734	-0.039570
+3.746410	0.026334	0.009576	9.801212	0.044100	0.088332	-0.038504
+3.747406	0.043093	-0.007182	9.844305	0.043966	0.089531	-0.035573
+3.748361	0.040699	0.000000	9.825152	0.045165	0.090997	-0.037838
+3.749400	-0.019152	-0.011970	9.726997	0.046498	0.087266	-0.034773
+3.750364	-0.002394	-0.038305	9.791636	0.048763	0.087666	-0.035972
+3.751404	0.002394	-0.038305	9.873033	0.047697	0.087533	-0.038371
+3.752351	-0.019152	-0.007182	9.825152	0.046231	0.086867	-0.036639
+3.753335	0.031123	-0.031123	9.806000	0.046498	0.085801	-0.038504
+3.754335	-0.028729	-0.009576	9.877821	0.049162	0.085401	-0.037971
+3.755334	-0.019152	-0.021546	9.777271	0.049029	0.089132	-0.035040
+3.756333	0.007182	0.009576	9.820364	0.046897	0.090730	-0.034507
+3.757334	-0.031123	-0.074215	9.722208	0.044899	0.088199	-0.037305
+3.758318	-0.031123	-0.062245	9.688692	0.046231	0.083802	-0.039037
+3.759334	-0.045487	-0.007182	9.798818	0.044632	0.083669	-0.035173
+3.760313	-0.023940	-0.023940	9.801212	0.047697	0.087400	-0.035839
+3.761342	-0.019152	-0.081397	9.899368	0.048763	0.091930	-0.039570
+3.762306	0.004788	-0.033517	9.820364	0.047297	0.092196	-0.039303
+3.763309	0.023940	0.052669	9.772483	0.044632	0.088199	-0.037172
+3.764335	-0.011970	0.014364	9.832334	0.045299	0.087266	-0.034374
+3.765340	0.004788	-0.023940	9.767695	0.044899	0.087799	-0.034107
+3.766345	-0.021546	0.021546	9.825152	0.045432	0.086734	-0.038637
+3.767340	-0.045487	0.002394	9.817970	0.047164	0.089132	-0.038371
+3.768334	-0.021546	-0.002394	9.803606	0.045432	0.092329	-0.035173
+3.769326	0.004788	-0.059851	9.875427	0.045565	0.090198	-0.033841
+3.770307	0.062245	-0.059851	9.782060	0.048496	0.088332	-0.034640
+3.771309	0.033517	-0.009576	9.746149	0.050628	0.088732	-0.039703
+3.772322	0.057457	-0.033517	9.772483	0.048096	0.089398	-0.039570
+3.773342	0.038305	0.014364	9.743755	0.047430	0.085934	-0.036639
+3.774308	0.000000	-0.038305	9.762907	0.048496	0.085534	-0.038904
+3.775406	-0.011970	-0.023940	9.827546	0.048230	0.088332	-0.039037
+3.776346	-0.028729	-0.043093	9.856275	0.047164	0.087799	-0.037838
+3.777347	-0.019152	0.002394	9.851487	0.046231	0.085002	-0.033841
+3.778350	0.043093	-0.007182	9.791636	0.045832	0.085534	-0.034773
+3.779411	0.033517	-0.035911	9.803606	0.046897	0.088466	-0.037172
+3.780407	-0.007182	-0.014364	9.726997	0.051028	0.088199	-0.036505
+3.781347	-0.026334	-0.033517	9.777271	0.051427	0.085668	-0.036106
+3.782371	-0.023940	-0.090974	9.810788	0.049828	0.084069	-0.038237
+3.783384	0.067033	-0.045487	9.789242	0.048629	0.087266	-0.036505
+3.784339	0.071821	0.000000	9.786848	0.048363	0.087133	-0.033974
+3.785311	0.079003	-0.023940	9.806000	0.047031	0.085534	-0.036639
+3.786407	-0.014364	0.000000	9.782060	0.044899	0.086467	-0.037571
+3.787406	-0.019152	0.004788	9.801212	0.043567	0.087799	-0.038104
+3.788345	0.026334	0.023940	9.789242	0.045432	0.089265	-0.038770
+3.789329	-0.002394	-0.007182	9.827546	0.046764	0.087533	-0.038104
+3.790393	0.009576	0.023940	9.777271	0.046498	0.085801	-0.037571
+3.791325	0.035911	0.014364	9.806000	0.047164	0.085401	-0.036772
+3.792317	0.045487	0.000000	9.738967	0.047031	0.088332	-0.035306
+3.793307	0.002394	0.002394	9.753331	0.044100	0.088998	-0.034507
+3.794283	0.011970	0.028729	9.765301	0.045165	0.088865	-0.035573
+3.795333	-0.059851	-0.026334	9.765301	0.047430	0.086067	-0.034374
+3.796283	-0.057457	-0.007182	9.837123	0.046897	0.084735	-0.037438
+3.797302	-0.057457	-0.007182	9.808394	0.048363	0.086067	-0.037305
+3.798307	0.014364	0.033517	9.808394	0.049029	0.088466	-0.034240
+3.799289	0.035911	-0.009576	9.782060	0.049429	0.089665	-0.034374
+3.800276	-0.004788	-0.009576	9.815576	0.046897	0.086734	-0.035972
+3.801300	-0.011970	0.016758	9.817970	0.044499	0.087933	-0.036905
+3.802286	-0.021546	0.014364	9.885003	0.047697	0.091530	-0.038504
+3.803324	-0.014364	0.021546	9.904156	0.049962	0.092995	-0.037172
+3.804298	-0.014364	0.014364	9.746149	0.049429	0.089398	-0.039170
+3.805319	0.019152	0.059851	9.686298	0.047697	0.085668	-0.036772
+3.806319	-0.043093	0.009576	9.753331	0.046231	0.085934	-0.036772
+3.807322	-0.026334	0.021546	9.782060	0.045698	0.085401	-0.037038
+3.808353	0.000000	0.000000	9.896974	0.045565	0.088066	-0.036505
+3.809305	0.016758	-0.011970	9.880215	0.045565	0.088466	-0.037438
+3.810326	-0.004788	0.011970	9.817970	0.046764	0.087799	-0.039703
+3.811322	-0.045487	-0.009576	9.755725	0.047164	0.088998	-0.036639
+3.812323	0.023940	-0.009576	9.820364	0.046364	0.089398	-0.033308
+3.813353	0.000000	-0.047881	9.832334	0.045698	0.089132	-0.029844
+3.814330	0.000000	0.009576	9.817970	0.046098	0.088332	-0.029311
+3.815339	0.079003	-0.033517	9.827546	0.047164	0.088732	-0.034507
+3.816377	0.021546	-0.031123	9.801212	0.049162	0.088599	-0.039703
+3.817384	0.055063	0.033517	9.849093	0.049029	0.088066	-0.037704
+3.818384	0.019152	0.047881	9.760513	0.047430	0.088732	-0.037172
+3.819326	0.033517	0.038305	9.686298	0.047430	0.089531	-0.039303
+3.820320	0.043093	0.002394	9.741361	0.044632	0.089931	-0.035972
+3.821321	0.026334	0.009576	9.839517	0.043700	0.089265	-0.035040
+3.822385	-0.045487	0.004788	9.844305	0.046364	0.088199	-0.035573
+3.823334	-0.023940	-0.004788	9.717420	0.046631	0.088332	-0.036772
+3.824326	0.002394	0.079003	9.820364	0.046764	0.087400	-0.037704
+3.825341	0.019152	0.028729	9.865851	0.048363	0.087266	-0.036905
+3.826329	-0.021546	0.016758	9.832334	0.049962	0.088199	-0.039836
+3.827381	-0.028729	0.000000	9.853881	0.049162	0.086867	-0.041035
+3.828383	-0.004788	-0.007182	9.832334	0.047963	0.085135	-0.039570
+3.829382	-0.002394	0.002394	9.779666	0.043300	0.087533	-0.036772
+3.830386	-0.028729	0.021546	9.810788	0.042501	0.088998	-0.037038
+3.831360	0.019152	-0.076609	9.877821	0.046231	0.086334	-0.035306
+3.832382	0.023940	-0.055063	9.856275	0.047164	0.086201	-0.035839
+3.833387	0.004788	-0.028729	9.777271	0.046498	0.087666	-0.037571
+3.834310	-0.004788	-0.050275	9.738967	0.045032	0.088865	-0.035706
+3.835289	-0.023940	-0.011970	9.813182	0.045832	0.089665	-0.037704
+3.836372	0.043093	-0.057457	9.861063	0.043567	0.087266	-0.037704
+3.837383	0.031123	-0.071821	9.779666	0.046098	0.084469	-0.035706
+3.838385	-0.002394	-0.011970	9.779666	0.046764	0.087133	-0.033574
+3.839326	0.052669	0.031123	9.892186	0.047430	0.088865	-0.035040
+3.840384	0.026334	0.007182	9.806000	0.048896	0.089132	-0.033308
+3.841385	0.026334	0.007182	9.806000	0.048629	0.088998	-0.035040
+3.842383	0.016758	0.040699	9.825152	0.045299	0.088599	-0.036106
+3.843382	0.062245	-0.019152	9.810788	0.044899	0.088865	-0.035972
+3.844321	0.062245	0.007182	9.815576	0.047697	0.086600	-0.035173
+3.845370	0.026334	0.035911	9.820364	0.048230	0.084868	-0.032375
+3.846349	0.028729	-0.028729	9.841911	0.049029	0.086867	-0.035839
+3.847383	0.086186	-0.014364	9.767695	0.049296	0.088732	-0.036639
+3.848382	0.016758	0.014364	9.741361	0.046498	0.090864	-0.038104
+3.849332	0.023940	-0.009576	9.767695	0.045832	0.090597	-0.039969
+3.850325	-0.009576	0.009576	9.794030	0.046231	0.088332	-0.039436
+3.851381	-0.055063	0.031123	9.810788	0.046897	0.089265	-0.039969
+3.852384	-0.021546	0.016758	9.822758	0.047430	0.088332	-0.036239
+3.853332	-0.035911	-0.043093	9.765301	0.048363	0.089531	-0.034640
+3.854350	0.002394	-0.011970	9.796424	0.047830	0.087266	-0.035573
+3.855307	-0.026334	0.004788	9.743755	0.046764	0.085934	-0.038104
+3.856383	0.019152	0.047881	9.676722	0.047963	0.087400	-0.037971
+3.857383	0.009576	0.040699	9.746149	0.048363	0.089265	-0.035040
+3.858421	-0.021546	0.011970	9.729391	0.045965	0.088599	-0.035972
+3.859332	-0.011970	0.021546	9.772483	0.048496	0.089398	-0.037971
+3.860441	0.000000	0.043093	9.801212	0.049429	0.086867	-0.035972
+3.861383	0.069427	-0.035911	9.849093	0.044499	0.086334	-0.035706
+3.862385	0.028729	-0.019152	9.796424	0.042101	0.088865	-0.034773
+3.863339	0.023940	-0.021546	9.794030	0.043567	0.088199	-0.035573
+3.864367	0.002394	0.009576	9.782060	0.047031	0.087799	-0.037571
+3.865346	0.035911	-0.007182	9.858669	0.048496	0.088332	-0.035440
+3.866385	0.047881	-0.050275	9.875427	0.047564	0.088332	-0.033175
+3.867382	-0.035911	-0.019152	9.839517	0.045965	0.087933	-0.033574
+3.868307	-0.031123	-0.009576	9.806000	0.046764	0.088466	-0.035040
+3.869321	-0.007182	-0.021546	9.815576	0.045698	0.088732	-0.039836
+3.870324	-0.009576	0.002394	9.813182	0.043034	0.089265	-0.041701
+3.871320	0.033517	-0.011970	9.762907	0.046897	0.086334	-0.037971
+3.872384	0.021546	-0.016758	9.810788	0.050095	0.084602	-0.037438
+3.873359	0.019152	0.002394	9.885003	0.048230	0.085002	-0.036905
+3.874264	-0.059851	-0.011970	9.825152	0.047031	0.085801	-0.029444
+3.875328	0.007182	-0.004788	9.834729	0.047164	0.086734	-0.032775
+3.876322	0.000000	-0.014364	9.806000	0.046897	0.089132	-0.036905
+3.877383	0.000000	-0.007182	9.794030	0.048096	0.090464	-0.038770
+3.878388	0.009576	0.023940	9.758119	0.047430	0.088732	-0.037172
+3.879382	-0.007182	-0.033517	9.765301	0.045698	0.088732	-0.037571
+3.880337	0.079003	0.023940	9.796424	0.045165	0.088466	-0.038504
+3.881323	0.040699	0.031123	9.846699	0.046098	0.087400	-0.036239
+3.882358	0.033517	-0.019152	9.825152	0.047297	0.087799	-0.035573
+3.883287	-0.009576	-0.004788	9.789242	0.049695	0.087000	-0.035573
+3.884299	-0.007182	0.028729	9.803606	0.049695	0.087799	-0.034240
+3.885317	0.052669	-0.011970	9.810788	0.049162	0.087666	-0.036639
+3.886383	0.043093	0.004788	9.803606	0.046631	0.088732	-0.034773
+3.887383	0.055063	0.028729	9.746149	0.046897	0.089398	-0.035972
+3.888382	0.067033	-0.016758	9.770089	0.047830	0.087799	-0.038504
+3.889330	-0.004788	0.000000	9.777271	0.046231	0.085401	-0.038104
+3.890335	0.000000	0.043093	9.868245	0.049029	0.090198	-0.036372
+3.891383	-0.014364	0.002394	9.935278	0.047297	0.090064	-0.036772
+3.892383	0.000000	-0.004788	9.846699	0.045565	0.084335	-0.034773
+3.893384	0.002394	-0.023940	9.765301	0.045565	0.086467	-0.035573
+3.894354	0.000000	0.016758	9.777271	0.045965	0.089398	-0.037971
+3.895345	-0.031123	-0.035911	9.779666	0.048230	0.088066	-0.034107
+3.896302	-0.052669	0.002394	9.786848	0.047031	0.087799	-0.031176
+3.897388	-0.055063	0.004788	9.839517	0.045832	0.087266	-0.033041
+3.898379	-0.007182	-0.038305	9.758119	0.046231	0.087799	-0.035306
+3.899385	0.076609	-0.040699	9.779666	0.044100	0.085934	-0.038637
+3.900324	0.000000	-0.050275	9.801212	0.045165	0.085801	-0.038904
+3.901330	-0.011970	0.014364	9.774877	0.046364	0.088066	-0.036905
+3.902383	0.014364	0.016758	9.820364	0.045565	0.089665	-0.035440
+3.903330	0.004788	-0.021546	9.837123	0.045432	0.089398	-0.033041
+3.904332	0.045487	0.004788	9.789242	0.043567	0.085135	-0.033308
+3.905319	0.007182	0.019152	9.753331	0.045698	0.084868	-0.036106
+3.906386	-0.028729	0.021546	9.729391	0.048763	0.088199	-0.034640
+3.907382	-0.021546	0.043093	9.755725	0.046098	0.090198	-0.037172
+3.908382	0.007182	-0.004788	9.817970	0.045565	0.088998	-0.041302
+3.909357	0.040699	-0.019152	9.796424	0.047031	0.088466	-0.037971
+3.910332	0.033517	-0.004788	9.813182	0.047830	0.087799	-0.034240
+3.911383	-0.014364	0.057457	9.825152	0.048096	0.087133	-0.036106
+3.912384	-0.004788	-0.004788	9.808394	0.048230	0.087666	-0.038504
+3.913325	0.000000	-0.019152	9.794030	0.045565	0.087133	-0.038104
+3.914311	-0.045487	-0.007182	9.822758	0.045698	0.089398	-0.036639
+3.915319	-0.016758	-0.023940	9.798818	0.049429	0.091530	-0.034507
+3.916308	0.045487	-0.081397	9.837123	0.048629	0.088599	-0.031842
+3.917341	0.043093	-0.035911	9.877821	0.047830	0.088066	-0.033841
+3.918303	0.002394	-0.028729	9.815576	0.046764	0.088599	-0.036905
+3.919302	-0.071821	-0.064639	9.837123	0.046897	0.090331	-0.035839
+3.920304	0.019152	-0.026334	9.829940	0.047697	0.088466	-0.036372
+3.921292	0.040699	0.028729	9.813182	0.048763	0.086734	-0.038104
+3.922310	0.009576	0.014364	9.827546	0.049296	0.085534	-0.036772
+3.923306	-0.028729	-0.026334	9.784454	0.048230	0.085135	-0.035040
+3.924283	-0.004788	-0.009576	9.817970	0.045832	0.088599	-0.034773
+3.925287	0.055063	0.083792	9.801212	0.044100	0.089132	-0.036372
+3.926334	0.028729	0.040699	9.806000	0.043833	0.087933	-0.035706
+3.927340	-0.007182	-0.019152	9.801212	0.044366	0.087000	-0.037172
+3.928327	-0.057457	-0.004788	9.832334	0.044766	0.085934	-0.038371
+3.929326	-0.045487	-0.031123	9.774877	0.047830	0.084868	-0.039037
+3.930330	-0.004788	-0.038305	9.806000	0.049562	0.088865	-0.039436
+3.931383	0.011970	0.002394	9.889792	0.051028	0.090198	-0.034107
+3.932382	0.045487	0.028729	9.851487	0.047430	0.087533	-0.033708
+3.933386	0.016758	-0.050275	9.822758	0.044632	0.086201	-0.034374
+3.934327	0.019152	-0.047881	9.789242	0.045965	0.086467	-0.035573
+3.935325	0.009576	-0.009576	9.844305	0.044366	0.088865	-0.034374
+3.936314	0.033517	0.004788	9.806000	0.044366	0.088466	-0.037704
+3.937341	0.040699	-0.043093	9.839517	0.047031	0.087799	-0.038371
+3.938348	0.004788	-0.055063	9.841911	0.046631	0.087266	-0.037305
+3.939351	0.074215	-0.045487	9.829940	0.047430	0.088732	-0.035839
+3.940329	0.028729	-0.016758	9.856275	0.045965	0.088732	-0.036239
+3.941356	0.059851	-0.007182	9.834729	0.047031	0.088998	-0.036106
+3.942358	0.014364	-0.023940	9.791636	0.047697	0.088199	-0.037438
+3.943320	0.040699	-0.031123	9.777271	0.048096	0.088998	-0.036639
+3.944319	-0.028729	-0.002394	9.734179	0.048363	0.090997	-0.032242
+3.945382	0.016758	-0.011970	9.789242	0.048363	0.088998	-0.033974
+3.946311	0.031123	-0.007182	9.779666	0.048363	0.086467	-0.036905
+3.947319	0.023940	-0.040699	9.798818	0.049029	0.086467	-0.038237
+3.948326	-0.021546	-0.004788	9.803606	0.049429	0.087133	-0.038904
+3.949303	-0.031123	0.057457	9.803606	0.048096	0.086467	-0.036639
+3.950328	0.057457	0.043093	9.767695	0.047963	0.086334	-0.036106
+3.951287	0.031123	-0.038305	9.791636	0.047297	0.086201	-0.037571
+3.952301	0.026334	-0.047881	9.817970	0.045965	0.088332	-0.036505
+3.953303	-0.009576	0.009576	9.853881	0.044632	0.088199	-0.035706
+3.954282	-0.021546	-0.009576	9.772483	0.045032	0.091397	-0.036106
+3.955302	-0.040699	-0.028729	9.841911	0.047031	0.089265	-0.037172
+3.956302	0.002394	-0.038305	9.779666	0.047564	0.086734	-0.036639
+3.957297	-0.011970	-0.026334	9.825152	0.047963	0.086334	-0.035839
+3.958302	-0.011970	-0.098156	9.827546	0.047164	0.086467	-0.036372
+3.959280	-0.043093	-0.062245	9.829940	0.048896	0.083936	-0.037971
+3.960279	0.047881	-0.067033	9.863457	0.049562	0.085801	-0.035839
+3.961302	0.055063	-0.019152	9.827546	0.049429	0.089531	-0.036372
+3.962263	0.028729	0.040699	9.782060	0.048363	0.090198	-0.036905
+3.963266	0.019152	0.062245	9.806000	0.048896	0.087533	-0.036239
+3.964266	0.016758	0.004788	9.849093	0.045832	0.085934	-0.036106
+3.965266	0.019152	0.009576	9.803606	0.046098	0.085534	-0.037704
+3.966267	0.016758	0.016758	9.794030	0.046631	0.086067	-0.036639
+3.967266	0.031123	-0.007182	9.849093	0.048496	0.087400	-0.036772
+3.968266	0.011970	-0.014364	9.865851	0.047830	0.088998	-0.035706
+3.969258	0.043093	0.009576	9.846699	0.046764	0.088332	-0.036372
+3.970262	0.023940	0.031123	9.817970	0.047963	0.089398	-0.038371
+3.971265	-0.062245	0.009576	9.772483	0.049296	0.088732	-0.036772
+3.972266	-0.035911	0.026334	9.803606	0.045565	0.088332	-0.035173
+3.973266	0.052669	-0.002394	9.796424	0.045698	0.087266	-0.035306
+3.974262	-0.002394	-0.011970	9.796424	0.047697	0.087400	-0.035573
+3.975275	0.052669	-0.009576	9.794030	0.050095	0.084868	-0.034773
+3.976266	0.043093	-0.050275	9.825152	0.049695	0.085668	-0.035306
+3.977265	0.014364	0.026334	9.777271	0.049029	0.089398	-0.034640
+3.978266	0.019152	0.031123	9.693480	0.046631	0.088332	-0.035306
+3.979344	0.004788	0.038305	9.760513	0.044899	0.085801	-0.035972
+3.980344	0.043093	0.026334	9.772483	0.047031	0.087400	-0.039303
+3.981301	0.004788	0.000000	9.865851	0.047430	0.089132	-0.036905
+3.982294	-0.002394	0.000000	9.908944	0.045565	0.088199	-0.038904
+3.983274	-0.019152	-0.038305	9.820364	0.050228	0.088066	-0.038104
+3.984263	0.023940	0.000000	9.724603	0.051028	0.086600	-0.037438
+3.985267	-0.011970	0.026334	9.748543	0.049162	0.086334	-0.036106
+3.986325	0.000000	0.014364	9.722208	0.046364	0.087266	-0.032775
+3.987318	-0.023940	0.021546	9.817970	0.043833	0.088998	-0.035440
+3.988350	0.009576	-0.002394	9.779666	0.043034	0.088466	-0.038237
+3.989358	0.016758	-0.035911	9.825152	0.046897	0.088066	-0.040902
+3.990332	0.011970	-0.079003	9.846699	0.047830	0.087666	-0.041035
+3.991326	-0.021546	-0.026334	9.777271	0.047564	0.087799	-0.040769
+3.992356	-0.014364	0.007182	9.758119	0.045032	0.087533	-0.037704
+3.993358	0.040699	0.016758	9.825152	0.045165	0.086600	-0.037172
+3.994356	0.040699	0.021546	9.863457	0.046631	0.087000	-0.035706
+3.995355	-0.011970	0.004788	9.801212	0.047164	0.087799	-0.036239
+3.996348	0.019152	0.009576	9.786848	0.046098	0.086600	-0.036372
+3.997327	0.031123	0.031123	9.810788	0.046897	0.087400	-0.037571
+3.998298	0.011970	0.045487	9.794030	0.047164	0.089132	-0.035040
+3.999326	-0.016758	-0.002394	9.803606	0.046498	0.090064	-0.038371
+4.000355	-0.019152	0.040699	9.784454	0.048896	0.089931	-0.041701
+4.001328	0.028729	0.021546	9.834729	0.047830	0.087933	-0.039836
+4.002357	0.007182	-0.059851	9.834729	0.047297	0.087933	-0.032375
+4.003328	0.014364	-0.023940	9.786848	0.046764	0.085534	-0.031975
+4.004289	0.014364	0.007182	9.784454	0.046098	0.087666	-0.033974
+4.005355	0.014364	-0.047881	9.762907	0.048096	0.085534	-0.036772
+4.006342	0.035911	-0.057457	9.755725	0.049962	0.086867	-0.041035
+4.007373	0.033517	-0.004788	9.779666	0.048496	0.088599	-0.041435
+4.008355	-0.011970	-0.007182	9.782060	0.048363	0.085534	-0.036372
+4.009356	0.023940	0.021546	9.796424	0.046897	0.083936	-0.031576
+4.010313	0.016758	0.033517	9.841911	0.046098	0.085135	-0.037571
+4.011349	0.014364	0.028729	9.825152	0.047430	0.086467	-0.037838
+4.012355	0.009576	-0.014364	9.810788	0.047697	0.089931	-0.035573
+4.013355	0.055063	-0.009576	9.719814	0.045832	0.091397	-0.034507
+4.014310	0.026334	0.004788	9.820364	0.047297	0.090730	-0.036905
+4.015328	0.004788	0.043093	9.784454	0.048763	0.089931	-0.036106
+4.016351	-0.038305	0.009576	9.832334	0.045832	0.089531	-0.037704
+4.017325	0.045487	0.023940	9.877821	0.045698	0.086600	-0.035173
+4.018308	0.009576	0.011970	9.801212	0.047963	0.085401	-0.036505
+4.019319	-0.019152	0.011970	9.762907	0.049828	0.088199	-0.036639
+4.020379	-0.028729	0.019152	9.794030	0.049695	0.087133	-0.034773
+4.021314	0.009576	0.038305	9.817970	0.050628	0.086734	-0.033974
+4.022385	-0.011970	-0.040699	9.863457	0.047830	0.086734	-0.034507
+4.023381	0.021546	-0.040699	9.784454	0.046764	0.088332	-0.036239
+4.024383	-0.031123	-0.026334	9.755725	0.046764	0.087000	-0.033574
+4.025376	0.009576	-0.057457	9.784454	0.045432	0.087400	-0.034107
+4.026381	0.011970	-0.021546	9.825152	0.046231	0.089531	-0.037305
+4.027323	-0.038305	0.040699	9.810788	0.047830	0.087266	-0.037704
+4.028304	0.026334	0.004788	9.750937	0.048363	0.087933	-0.035306
+4.029326	0.059851	-0.050275	9.794030	0.049962	0.089265	-0.035306
+4.030323	-0.014364	-0.035911	9.863457	0.045965	0.090864	-0.034374
+4.031320	-0.028729	-0.011970	9.882609	0.045565	0.089132	-0.038504
+4.032381	0.052669	0.033517	9.846699	0.047297	0.086600	-0.038770
+4.033381	0.035911	0.016758	9.782060	0.045432	0.086467	-0.035173
+4.034349	-0.019152	-0.047881	9.796424	0.047697	0.088732	-0.036905
+4.035312	-0.028729	-0.019152	9.825152	0.047697	0.089398	-0.038637
+4.036320	0.007182	-0.009576	9.810788	0.045165	0.087133	-0.039969
+4.037345	-0.019152	0.007182	9.853881	0.044632	0.084469	-0.038371
+4.038322	0.004788	0.007182	9.887397	0.047564	0.087266	-0.037038
+4.039323	0.000000	0.011970	9.861063	0.049695	0.090464	-0.038770
+4.040289	-0.004788	-0.023940	9.827546	0.049162	0.090864	-0.038904
+4.041301	-0.035911	-0.047881	9.794030	0.046498	0.090064	-0.036106
+4.042322	-0.050275	-0.016758	9.832334	0.045032	0.088998	-0.034374
+4.043314	-0.028729	0.038305	9.789242	0.045565	0.089665	-0.031975
+4.044319	0.050275	0.040699	9.717420	0.046498	0.088466	-0.034374
+4.045320	0.035911	0.052669	9.746149	0.050228	0.087266	-0.039570
+4.046319	0.067033	0.035911	9.789242	0.049562	0.087133	-0.039570
+4.047300	0.052669	0.014364	9.784454	0.048230	0.091663	-0.035972
+4.048315	0.045487	0.007182	9.810788	0.047830	0.092596	-0.036639
+4.049379	0.033517	-0.004788	9.815576	0.049296	0.087799	-0.035972
+4.050385	0.026334	-0.019152	9.786848	0.048496	0.087133	-0.037038
+4.051338	0.031123	0.004788	9.803606	0.047963	0.088865	-0.035040
+4.052319	-0.057457	-0.004788	9.856275	0.049296	0.090064	-0.037305
+4.053381	-0.014364	0.000000	9.762907	0.050361	0.089398	-0.038237
+4.054324	0.050275	0.000000	9.822758	0.048363	0.086467	-0.036505
+4.055321	0.011970	0.009576	9.863457	0.045698	0.086734	-0.034107
+4.056321	-0.004788	-0.016758	9.808394	0.043167	0.085135	-0.032908
+4.057323	0.011970	-0.040699	9.753331	0.045965	0.086867	-0.035972
+4.058382	-0.002394	-0.067033	9.806000	0.047297	0.089265	-0.036639
+4.059327	-0.007182	0.035911	9.801212	0.049828	0.088599	-0.036239
+4.060326	-0.011970	-0.002394	9.858669	0.047697	0.085668	-0.033574
+4.061380	0.002394	-0.033517	9.791636	0.046098	0.085534	-0.036239
+4.062386	-0.026334	-0.007182	9.770089	0.046897	0.088466	-0.040103
+4.063380	0.000000	0.011970	9.765301	0.047963	0.089265	-0.039037
+4.064382	0.028729	-0.009576	9.794030	0.047297	0.088199	-0.039037
+4.065383	-0.007182	-0.028729	9.853881	0.046231	0.086734	-0.033974
+4.066383	0.014364	-0.038305	9.832334	0.045032	0.086734	-0.032109
+4.067314	0.038305	-0.045487	9.817970	0.044499	0.085934	-0.033708
+4.068340	-0.004788	-0.064639	9.868245	0.046631	0.086334	-0.037704
+4.069374	-0.007182	-0.038305	9.808394	0.046764	0.086600	-0.038237
+4.070324	0.004788	0.026334	9.813182	0.043433	0.085934	-0.035839
+4.071290	-0.021546	-0.009576	9.877821	0.042900	0.086867	-0.035440
+4.072382	-0.007182	-0.026334	9.808394	0.047697	0.088066	-0.038371
+4.073384	0.019152	-0.045487	9.846699	0.048763	0.088732	-0.036239
+4.074384	-0.004788	-0.016758	9.782060	0.047297	0.088066	-0.036905
+4.075322	0.026334	0.040699	9.760513	0.048096	0.089398	-0.038104
+4.076380	-0.016758	-0.031123	9.772483	0.048363	0.088332	-0.036639
+4.077347	-0.009576	-0.011970	9.784454	0.046631	0.087400	-0.038237
+4.078339	-0.026334	0.076609	9.810788	0.046498	0.089132	-0.036905
+4.079382	-0.047881	0.016758	9.911338	0.046764	0.090464	-0.035706
+4.080383	-0.023940	-0.016758	9.863457	0.045565	0.090064	-0.034907
+4.081381	0.045487	-0.055063	9.791636	0.045565	0.088599	-0.034240
+4.082361	0.035911	-0.016758	9.734179	0.045165	0.088599	-0.034907
+4.083382	-0.004788	0.007182	9.875427	0.043433	0.089265	-0.035440
+4.084382	-0.007182	0.007182	9.911338	0.041835	0.085401	-0.033974
+4.085338	-0.019152	0.007182	9.887397	0.043833	0.084735	-0.033441
+4.086321	0.004788	0.021546	9.873033	0.048230	0.088066	-0.037038
+4.087334	-0.055063	-0.033517	9.844305	0.048096	0.089265	-0.037305
+4.088325	-0.069427	0.002394	9.825152	0.046631	0.088199	-0.038237
+4.089379	-0.014364	0.007182	9.772483	0.046498	0.089265	-0.036239
+4.090384	-0.023940	0.009576	9.767695	0.046231	0.089798	-0.037838
+4.091318	-0.038305	0.016758	9.822758	0.047830	0.089931	-0.035706
+4.092282	-0.009576	0.040699	9.746149	0.047297	0.089665	-0.033574
+4.093282	0.038305	-0.026334	9.734179	0.049029	0.091130	-0.035040
+4.094293	0.004788	-0.019152	9.772483	0.047963	0.091930	-0.035306
+4.095284	-0.009576	0.052669	9.808394	0.048363	0.090198	-0.034374
+4.096270	-0.004788	-0.004788	9.784454	0.046364	0.089398	-0.036772
+4.097287	-0.028729	0.014364	9.813182	0.047297	0.087933	-0.039969
+4.098328	-0.026334	0.055063	9.858669	0.045965	0.086867	-0.037172
+4.099326	0.016758	0.019152	9.875427	0.045565	0.087133	-0.036239
+4.100307	0.026334	-0.019152	9.880215	0.046897	0.087266	-0.035972
+4.101280	0.057457	-0.067033	9.789242	0.047031	0.087933	-0.038504
+4.102313	0.028729	0.040699	9.779666	0.046897	0.090864	-0.036372
+4.103325	0.016758	0.004788	9.786848	0.046631	0.088332	-0.033175
+4.104325	0.043093	-0.014364	9.806000	0.049029	0.086867	-0.037438
+4.105293	0.081397	0.021546	9.789242	0.048496	0.084735	-0.035573
+4.106326	0.009576	-0.019152	9.779666	0.048763	0.086734	-0.035706
+4.107325	0.035911	-0.004788	9.846699	0.047564	0.087666	-0.036505
+4.108328	0.011970	0.067033	9.810788	0.045165	0.086600	-0.037838
+4.109295	0.055063	0.016758	9.813182	0.045698	0.085668	-0.038104
+4.110262	0.031123	-0.043093	9.777271	0.047164	0.086867	-0.034507
+4.111259	0.004788	-0.040699	9.722208	0.047031	0.088599	-0.037172
+4.112256	0.009576	-0.038305	9.724603	0.046231	0.088599	-0.038104
+4.113264	0.040699	-0.004788	9.822758	0.045965	0.088865	-0.037172
+4.114264	0.071821	-0.047881	9.865851	0.045698	0.087933	-0.039303
+4.115278	0.031123	-0.002394	9.837123	0.046631	0.089398	-0.034907
+4.116265	-0.035911	0.021546	9.832334	0.045832	0.088732	-0.034773
+4.117249	0.007182	-0.007182	9.834729	0.047164	0.088732	-0.035440
+4.118251	-0.023940	-0.009576	9.767695	0.045965	0.090331	-0.034507
+4.119247	0.016758	-0.014364	9.722208	0.045832	0.089132	-0.034240
+4.120261	0.011970	0.031123	9.746149	0.047031	0.090464	-0.037038
+4.121261	0.002394	0.016758	9.832334	0.048763	0.089531	-0.032908
+4.122258	0.028729	0.031123	9.782060	0.049828	0.088732	-0.034907
+4.123250	-0.019152	-0.069427	9.762907	0.050095	0.088599	-0.037704
+4.124241	0.000000	0.019152	9.885003	0.048763	0.087533	-0.037571
+4.125241	0.016758	-0.019152	9.856275	0.047697	0.087400	-0.037971
+4.126240	0.040699	-0.088580	9.789242	0.046364	0.086734	-0.037838
+4.127250	0.016758	-0.083792	9.820364	0.045299	0.087266	-0.038770
+4.128244	0.035911	-0.050275	9.774877	0.045832	0.087400	-0.036905
+4.129239	-0.002394	-0.014364	9.832334	0.049429	0.087533	-0.037971
+4.130238	0.011970	-0.031123	9.870639	0.051161	0.088332	-0.036106
+4.131238	0.019152	0.009576	9.870639	0.050495	0.087000	-0.036505
+4.132242	-0.007182	0.004788	9.856275	0.045565	0.087133	-0.037838
+4.133258	0.023940	0.023940	9.806000	0.044499	0.086467	-0.037971
+4.134264	0.045487	-0.011970	9.815576	0.044766	0.085934	-0.033308
+4.135245	0.067033	-0.004788	9.789242	0.047430	0.086734	-0.035173
+4.136264	0.043093	-0.016758	9.810788	0.047830	0.086734	-0.037038
+4.137249	0.019152	-0.016758	9.791636	0.046231	0.088599	-0.036905
+4.138252	0.014364	0.011970	9.784454	0.044100	0.088599	-0.037838
+4.139263	0.016758	-0.011970	9.841911	0.046631	0.088865	-0.037571
+4.140259	0.055063	-0.045487	9.849093	0.048096	0.089931	-0.036106
+4.141249	0.011970	-0.033517	9.837123	0.048496	0.087133	-0.035972
+4.142255	0.016758	-0.093368	9.827546	0.049562	0.086201	-0.037571
+4.143255	-0.007182	-0.026334	9.817970	0.048896	0.087400	-0.034640
+4.144277	0.016758	-0.023940	9.791636	0.046364	0.088466	-0.036772
+4.145276	0.009576	0.014364	9.837123	0.044632	0.090331	-0.035706
+4.146290	-0.014364	0.019152	9.750937	0.044499	0.088466	-0.035173
+4.147342	-0.079003	0.031123	9.801212	0.045832	0.086201	-0.037305
+4.148279	0.002394	0.043093	9.810788	0.048496	0.086734	-0.036772
+4.149284	0.023940	0.019152	9.784454	0.048629	0.087533	-0.033841
+4.150277	-0.002394	-0.043093	9.868245	0.048896	0.085668	-0.033574
+4.151261	0.009576	-0.007182	9.825152	0.045565	0.086201	-0.037971
+4.152276	0.071821	0.045487	9.868245	0.046498	0.086600	-0.037438
+4.153254	-0.004788	0.002394	9.839517	0.046897	0.086467	-0.035306
+4.154297	-0.031123	-0.033517	9.791636	0.046098	0.088466	-0.036772
+4.155305	-0.004788	-0.004788	9.772483	0.047963	0.088865	-0.036505
+4.156262	0.009576	-0.033517	9.817970	0.046364	0.089531	-0.033974
+4.157276	-0.045487	0.038305	9.782060	0.047697	0.090064	-0.035839
+4.158277	-0.011970	0.031123	9.794030	0.045565	0.090064	-0.035573
+4.159282	0.021546	0.009576	9.772483	0.043833	0.090597	-0.038637
+4.160291	0.000000	-0.021546	9.726997	0.045698	0.088865	-0.039570
+4.161293	0.002394	0.000000	9.710238	0.047031	0.088466	-0.037971
+4.162339	0.011970	-0.033517	9.791636	0.048629	0.087799	-0.038904
+4.163293	0.011970	-0.050275	9.863457	0.047697	0.087666	-0.036772
+4.164295	0.045487	-0.035911	9.786848	0.048363	0.090597	-0.037971
+4.165286	0.059851	-0.040699	9.837123	0.049695	0.089265	-0.037172
+4.166289	0.028729	-0.011970	9.858669	0.045299	0.087266	-0.037038
+4.167291	0.035911	-0.019152	9.738967	0.042767	0.086600	-0.037438
+4.168257	0.014364	-0.035911	9.772483	0.045432	0.086067	-0.037438
+4.169271	0.002394	0.000000	9.827546	0.047697	0.087000	-0.038504
+4.170298	-0.016758	0.052669	9.829940	0.048363	0.089531	-0.040369
+4.171267	0.007182	0.028729	9.851487	0.049429	0.088066	-0.037305
+4.172292	-0.028729	0.000000	9.798818	0.046498	0.088199	-0.037438
+4.173294	-0.059851	-0.074215	9.762907	0.045032	0.088199	-0.038770
+4.174298	-0.023940	-0.028729	9.794030	0.045032	0.090198	-0.039703
+4.175343	-0.035911	-0.028729	9.832334	0.045832	0.088599	-0.035306
+4.176343	-0.023940	-0.004788	9.849093	0.043300	0.088865	-0.034640
+4.177342	0.011970	0.035911	9.772483	0.044632	0.088599	-0.035306
+4.178327	-0.007182	0.038305	9.736573	0.044766	0.088199	-0.036772
+4.179342	0.019152	0.040699	9.760513	0.043966	0.089265	-0.037704
+4.180324	0.059851	0.016758	9.686298	0.046631	0.088732	-0.038504
+4.181339	-0.004788	-0.007182	9.774877	0.047830	0.089931	-0.038104
+4.182347	-0.019152	-0.023940	9.856275	0.047430	0.090464	-0.034374
+4.183341	-0.043093	-0.038305	9.827546	0.047297	0.087533	-0.035839
+4.184343	-0.069427	-0.019152	9.794030	0.046498	0.085934	-0.035706
+4.185297	-0.035911	0.011970	9.786848	0.045032	0.087666	-0.034374
+4.186342	0.016758	0.007182	9.772483	0.047031	0.088865	-0.038104
+4.187343	0.011970	-0.035911	9.717420	0.048096	0.088865	-0.035706
+4.188275	-0.004788	-0.031123	9.760513	0.046764	0.089665	-0.034907
+4.189340	0.038305	-0.009576	9.774877	0.045832	0.090730	-0.037838
+4.190286	0.043093	-0.026334	9.808394	0.045565	0.089798	-0.041302
+4.191334	0.026334	0.002394	9.815576	0.046364	0.087400	-0.039303
+4.192337	0.045487	0.031123	9.784454	0.044766	0.087799	-0.036905
+4.193343	-0.021546	-0.016758	9.717420	0.047564	0.089531	-0.033974
+4.194342	-0.016758	-0.004788	9.719814	0.048896	0.090464	-0.034507
+4.195342	0.028729	0.000000	9.806000	0.047830	0.090198	-0.036505
+4.196341	0.011970	0.043093	9.877821	0.044766	0.089665	-0.037438
+4.197343	-0.047881	0.040699	9.885003	0.045165	0.087666	-0.033974
+4.198341	-0.035911	-0.004788	9.846699	0.046231	0.087799	-0.032508
+4.199293	0.009576	-0.019152	9.808394	0.045032	0.089398	-0.035306
+4.200333	0.033517	-0.021546	9.820364	0.045032	0.089665	-0.037838
+4.201282	0.035911	-0.045487	9.865851	0.046364	0.087533	-0.037438
+4.202348	0.040699	-0.009576	9.774877	0.045965	0.087533	-0.035306
+4.203342	-0.002394	0.026334	9.858669	0.044766	0.088466	-0.034507
+4.204290	0.067033	0.026334	9.870639	0.045299	0.089931	-0.036905
+4.205331	0.064639	-0.004788	9.887397	0.047963	0.090864	-0.039303
+4.206291	0.033517	0.021546	9.856275	0.048763	0.089665	-0.033841
+4.207282	0.011970	-0.004788	9.772483	0.047963	0.089531	-0.035440
+4.208342	0.062245	0.014364	9.746149	0.045165	0.087666	-0.039436
+4.209344	0.033517	-0.019152	9.779666	0.044499	0.087000	-0.040902
+4.210364	-0.028729	0.007182	9.794030	0.046498	0.091130	-0.037971
+4.211317	0.004788	0.009576	9.777271	0.047564	0.092329	-0.035306
+4.212303	0.016758	0.019152	9.815576	0.046631	0.088199	-0.034907
+4.213299	-0.028729	-0.033517	9.846699	0.046764	0.085801	-0.036505
+4.214295	-0.016758	-0.007182	9.820364	0.048363	0.087933	-0.035706
+4.215342	-0.069427	0.000000	9.796424	0.046631	0.088066	-0.038237
+4.216305	0.016758	0.007182	9.837123	0.045565	0.086334	-0.039969
+4.217343	0.067033	-0.019152	9.834729	0.046098	0.085801	-0.037038
+4.218278	0.021546	-0.055063	9.803606	0.045965	0.085668	-0.037172
+4.219294	0.028729	0.002394	9.841911	0.047031	0.087666	-0.039436
+4.220291	0.026334	-0.007182	9.815576	0.048230	0.086734	-0.039703
+4.221320	-0.016758	-0.031123	9.748543	0.047164	0.087400	-0.038237
+4.222293	0.007182	-0.009576	9.798818	0.044766	0.089798	-0.033974
+4.223274	-0.002394	0.009576	9.806000	0.044899	0.089665	-0.033175
+4.224302	0.007182	-0.026334	9.861063	0.045565	0.088998	-0.032908
+4.225343	0.009576	0.016758	9.782060	0.045165	0.087533	-0.036372
+4.226359	0.009576	-0.021546	9.770089	0.045032	0.088998	-0.035706
+4.227401	0.059851	-0.038305	9.858669	0.046498	0.088865	-0.034507
+4.228399	0.011970	0.043093	9.796424	0.047430	0.090997	-0.041035
+4.229402	-0.016758	-0.019152	9.784454	0.047697	0.090997	-0.040502
+4.230405	0.004788	-0.047881	9.779666	0.045032	0.085934	-0.036106
+4.231401	-0.038305	-0.009576	9.719814	0.045698	0.085002	-0.037438
+4.232367	-0.004788	-0.026334	9.765301	0.045832	0.086067	-0.038237
+4.233327	0.031123	0.004788	9.748543	0.046764	0.085135	-0.038104
+4.234399	0.031123	0.019152	9.798818	0.048629	0.087000	-0.037971
+4.235337	0.033517	0.035911	9.846699	0.049695	0.087000	-0.034773
+4.236400	-0.011970	-0.028729	9.724603	0.048096	0.086334	-0.035306
+4.237400	-0.011970	-0.023940	9.719814	0.047564	0.088199	-0.035040
+4.238361	0.035911	-0.014364	9.755725	0.047697	0.088599	-0.037571
+4.239400	0.002394	-0.033517	9.784454	0.048230	0.091397	-0.038237
+4.240403	0.014364	-0.004788	9.782060	0.046231	0.088332	-0.041168
+4.241402	-0.004788	-0.011970	9.827546	0.045565	0.084868	-0.035972
+4.242508	-0.057457	-0.023940	9.820364	0.045698	0.085401	-0.032508
+4.243313	-0.050275	-0.052669	9.808394	0.046764	0.086600	-0.034640
+4.244313	-0.040699	-0.057457	9.760513	0.047564	0.085801	-0.038237
+4.245297	-0.004788	0.016758	9.834729	0.047564	0.086334	-0.041035
+4.246333	0.004788	0.062245	9.834729	0.047031	0.086334	-0.042634
+4.247302	-0.023940	0.019152	9.772483	0.046631	0.086734	-0.037971
+4.248333	-0.045487	0.007182	9.659963	0.047963	0.091663	-0.037305
+4.249333	-0.045487	-0.033517	9.695874	0.046631	0.089665	-0.040103
+4.250304	-0.028729	-0.004788	9.806000	0.045165	0.087000	-0.038237
+4.251332	-0.016758	0.011970	9.700662	0.046631	0.086467	-0.034640
+4.252300	-0.009576	-0.028729	9.738967	0.047564	0.087400	-0.036905
+4.253326	-0.019152	-0.062245	9.796424	0.045965	0.087799	-0.039037
+4.254331	-0.028729	-0.002394	9.851487	0.046098	0.089265	-0.039703
+4.255325	-0.007182	-0.026334	9.813182	0.047430	0.088199	-0.033974
+4.256384	0.045487	-0.004788	9.760513	0.049029	0.085268	-0.035040
+4.257337	-0.007182	-0.040699	9.715026	0.048096	0.084335	-0.036106
+4.258345	-0.057457	-0.045487	9.755725	0.045698	0.087533	-0.037172
+4.259349	-0.011970	-0.014364	9.806000	0.043433	0.089265	-0.034507
+4.260346	-0.009576	0.000000	9.803606	0.044233	0.086867	-0.035573
+4.261309	0.000000	-0.023940	9.777271	0.046498	0.086334	-0.036905
+4.262404	-0.002394	-0.002394	9.808394	0.046098	0.087666	-0.036905
+4.263402	0.002394	-0.016758	9.856275	0.045432	0.089132	-0.035040
+4.264362	0.023940	0.026334	9.846699	0.045032	0.088599	-0.036372
+4.265362	0.028729	0.004788	9.846699	0.044632	0.086600	-0.037838
+4.266336	0.033517	-0.002394	9.786848	0.045698	0.087666	-0.034907
+4.267401	0.040699	0.009576	9.827546	0.046764	0.088332	-0.033175
+4.268330	0.019152	-0.095762	9.813182	0.045565	0.090597	-0.035173
+4.269401	-0.023940	-0.023940	9.710238	0.044766	0.089798	-0.038770
+4.270406	-0.011970	0.000000	9.849093	0.047164	0.089265	-0.039170
+4.271359	0.002394	0.023940	9.765301	0.046498	0.090064	-0.038237
+4.272313	0.028729	0.014364	9.772483	0.044233	0.090730	-0.035573
+4.273307	-0.031123	0.023940	9.849093	0.047031	0.088199	-0.035573
+4.274308	-0.035911	0.000000	9.875427	0.047830	0.086867	-0.034240
+4.275307	-0.021546	0.007182	9.717420	0.050228	0.088332	-0.035706
+4.276309	-0.004788	0.000000	9.798818	0.050495	0.088599	-0.033441
+4.277310	0.019152	-0.040699	9.789242	0.045965	0.086734	-0.033308
+4.278312	0.016758	0.002394	9.803606	0.044233	0.087133	-0.033574
+4.279310	0.011970	-0.038305	9.774877	0.047164	0.089798	-0.036905
+4.280311	-0.026334	-0.026334	9.803606	0.051694	0.090198	-0.039703
+4.281287	-0.011970	0.007182	9.798818	0.049429	0.087533	-0.039170
+4.282307	0.019152	-0.045487	9.827546	0.046364	0.087799	-0.036772
+4.283286	0.040699	-0.057457	9.738967	0.047164	0.086334	-0.035440
+4.284289	0.040699	-0.026334	9.746149	0.046098	0.085401	-0.038904
+4.285310	-0.011970	0.016758	9.738967	0.046631	0.086067	-0.037172
+4.286251	0.019152	-0.016758	9.837123	0.047297	0.087799	-0.034640
+4.287253	0.076609	-0.047881	9.779666	0.047830	0.086067	-0.033841
+4.288243	0.059851	-0.007182	9.772483	0.046231	0.085668	-0.034374
+4.289244	0.009576	0.028729	9.801212	0.045832	0.089931	-0.036772
+4.290306	0.019152	0.057457	9.868245	0.045032	0.090064	-0.037704
+4.291250	0.002394	0.016758	9.832334	0.045565	0.086334	-0.036239
+4.292239	0.021546	0.031123	9.707844	0.044632	0.084868	-0.036239
+4.293243	0.043093	-0.023940	9.717420	0.043833	0.087666	-0.037305
+4.294243	0.040699	-0.031123	9.729391	0.045965	0.087799	-0.038237
+4.295242	0.028729	0.011970	9.659963	0.045032	0.090597	-0.036772
+4.296243	0.045487	0.014364	9.746149	0.046897	0.089798	-0.036505
+4.297243	0.045487	0.040699	9.817970	0.049429	0.089798	-0.037838
+4.298300	0.016758	0.023940	9.808394	0.049695	0.090064	-0.039969
+4.299288	0.011970	0.007182	9.798818	0.046631	0.086867	-0.038904
+4.300325	-0.028729	-0.028729	9.726997	0.045299	0.085268	-0.037172
+4.301316	0.016758	0.023940	9.825152	0.045432	0.086201	-0.035972
+4.302342	0.023940	0.016758	9.827546	0.046098	0.087933	-0.033574
+4.303343	0.035911	-0.035911	9.810788	0.046364	0.085934	-0.032508
+4.304343	0.011970	-0.064639	9.885003	0.047430	0.088332	-0.036772
+4.305343	0.050275	-0.016758	9.803606	0.048363	0.088998	-0.034640
+4.306345	0.069427	0.000000	9.849093	0.049962	0.088732	-0.035573
+4.307340	0.014364	-0.047881	9.734179	0.048363	0.088466	-0.035706
+4.308286	-0.016758	-0.021546	9.679116	0.047564	0.087533	-0.036372
+4.309341	0.035911	0.011970	9.786848	0.046897	0.088199	-0.036505
+4.310290	-0.033517	-0.011970	9.870639	0.046364	0.090864	-0.036905
+4.311280	0.014364	0.026334	9.829940	0.045165	0.089931	-0.037038
+4.312341	0.035911	-0.040699	9.772483	0.046364	0.086467	-0.036905
+4.313344	0.026334	-0.019152	9.817970	0.046231	0.088466	-0.038504
+4.314343	0.076609	0.002394	9.844305	0.047697	0.089132	-0.038504
+4.315342	0.023940	0.021546	9.877821	0.049828	0.087533	-0.036239
+4.316343	0.009576	-0.019152	9.853881	0.048363	0.085801	-0.034640
+4.317341	0.031123	-0.038305	9.892186	0.046364	0.087799	-0.035706
+4.318338	0.004788	-0.009576	9.784454	0.048230	0.087533	-0.036772
+4.319341	-0.004788	0.028729	9.719814	0.047963	0.086600	-0.037038
+4.320342	-0.004788	0.031123	9.719814	0.045698	0.089398	-0.035306
+4.321302	0.002394	-0.045487	9.762907	0.046498	0.092462	-0.032908
+4.322308	-0.026334	0.067033	9.806000	0.049562	0.091130	-0.034773
+4.323286	0.002394	-0.007182	9.803606	0.048763	0.092462	-0.034240
+4.324401	0.019152	-0.062245	9.750937	0.043700	0.092329	-0.033574
+4.325401	-0.011970	-0.086186	9.767695	0.041701	0.089398	-0.035972
+4.326333	-0.002394	-0.088580	9.722208	0.044366	0.086600	-0.036905
+4.327400	0.016758	-0.067033	9.750937	0.047164	0.085668	-0.033708
+4.328336	0.026334	-0.043093	9.774877	0.048096	0.086600	-0.032908
+4.329405	-0.023940	0.007182	9.858669	0.045698	0.086067	-0.036905
+4.330403	-0.007182	-0.038305	9.784454	0.044766	0.087000	-0.037305
+4.331376	0.019152	0.031123	9.777271	0.045299	0.087133	-0.039303
+4.332396	0.071821	-0.035911	9.796424	0.046098	0.087266	-0.039836
+4.333403	0.064639	0.009576	9.856275	0.047430	0.087666	-0.039836
+4.334403	0.014364	-0.033517	9.829940	0.049029	0.087799	-0.037038
+4.335341	-0.026334	-0.026334	9.794030	0.046098	0.088865	-0.037971
+4.336401	-0.028729	0.004788	9.806000	0.046631	0.089531	-0.036505
+4.337405	0.016758	0.040699	9.851487	0.048230	0.090331	-0.035839
+4.338326	-0.016758	0.028729	9.796424	0.046631	0.086600	-0.037704
+4.339369	-0.004788	-0.033517	9.748543	0.045565	0.085135	-0.041568
+4.340345	0.021546	-0.004788	9.738967	0.047297	0.089132	-0.036106
+4.341401	0.045487	0.023940	9.817970	0.046897	0.087933	-0.035306
+4.342404	0.021546	-0.004788	9.827546	0.046631	0.086734	-0.036106
+4.343402	0.000000	-0.007182	9.806000	0.050095	0.088199	-0.037704
+4.344332	0.031123	-0.033517	9.815576	0.047830	0.090064	-0.040769
+4.345400	0.000000	-0.045487	9.894580	0.044766	0.090997	-0.037305
+4.346340	0.007182	-0.079003	9.885003	0.045698	0.089665	-0.034107
+4.347298	0.040699	-0.047881	9.806000	0.045299	0.086067	-0.035972
+4.348317	0.081397	-0.050275	9.808394	0.047830	0.085934	-0.036639
+4.349307	0.052669	-0.033517	9.784454	0.048629	0.085801	-0.036106
+4.350297	0.038305	-0.009576	9.803606	0.052093	0.086600	-0.035839
+4.351336	0.069427	0.043093	9.779666	0.051294	0.087400	-0.035306
+4.352377	0.040699	0.002394	9.786848	0.048496	0.088865	-0.036106
+4.353402	-0.035911	0.009576	9.844305	0.046764	0.087133	-0.036372
+4.354407	-0.050275	-0.011970	9.863457	0.046631	0.087533	-0.039170
+4.355402	0.021546	-0.023940	9.880215	0.046631	0.089665	-0.036239
+4.356402	0.052669	0.040699	9.863457	0.046364	0.088865	-0.036905
+4.357363	0.000000	0.009576	9.817970	0.043833	0.086201	-0.035839
+4.358412	0.028729	-0.002394	9.794030	0.043700	0.084868	-0.036639
+4.359382	0.067033	0.050275	9.794030	0.047031	0.089265	-0.037571
+4.360345	0.021546	-0.038305	9.825152	0.049162	0.089265	-0.035440
+4.361374	-0.011970	-0.023940	9.791636	0.048096	0.089398	-0.034107
+4.362406	0.007182	-0.009576	9.813182	0.046764	0.088066	-0.032775
+4.363400	0.045487	-0.016758	9.820364	0.046498	0.087666	-0.035972
+4.364402	0.011970	-0.011970	9.820364	0.046897	0.087533	-0.038504
+4.365401	0.062245	0.016758	9.808394	0.049429	0.087266	-0.039836
+4.366402	0.000000	0.007182	9.791636	0.049429	0.088466	-0.039703
+4.367358	-0.033517	-0.038305	9.686298	0.047564	0.089798	-0.036772
+4.368350	-0.002394	-0.055063	9.791636	0.047031	0.085668	-0.035573
+4.369401	0.019152	0.007182	9.822758	0.047963	0.085401	-0.037704
+4.370404	0.014364	0.083792	9.829940	0.047963	0.084335	-0.036772
+4.371401	0.026334	-0.016758	9.750937	0.047697	0.087533	-0.033974
+4.372336	0.038305	-0.047881	9.789242	0.047031	0.090597	-0.031975
+4.373401	-0.052669	-0.026334	9.774877	0.045432	0.093662	-0.034640
+4.374406	-0.014364	-0.019152	9.791636	0.046498	0.092196	-0.036905
+4.375405	0.016758	0.035911	9.750937	0.047697	0.085401	-0.036905
+4.376336	-0.023940	0.021546	9.791636	0.048763	0.083270	-0.036372
+4.377298	0.011970	-0.009576	9.746149	0.049429	0.086067	-0.038371
+4.378375	0.095762	-0.019152	9.758119	0.046897	0.089665	-0.035706
+4.379319	0.059851	-0.016758	9.748543	0.044499	0.089265	-0.034773
+4.380355	-0.023940	0.035911	9.803606	0.047031	0.087133	-0.036772
+4.381342	-0.016758	-0.007182	9.789242	0.048230	0.086867	-0.040902
+4.382328	-0.007182	-0.062245	9.806000	0.048896	0.084469	-0.040769
+4.383307	0.023940	-0.047881	9.777271	0.049029	0.084868	-0.034107
+4.384321	-0.045487	-0.035911	9.806000	0.047963	0.088199	-0.033974
+4.385310	0.009576	-0.009576	9.803606	0.047031	0.088466	-0.034107
+4.386335	0.067033	0.033517	9.736573	0.045832	0.086334	-0.036372
+4.387399	0.033517	0.002394	9.762907	0.044366	0.086467	-0.036239
+4.388340	-0.004788	-0.011970	9.786848	0.047830	0.085801	-0.037971
+4.389353	0.023940	-0.021546	9.794030	0.048763	0.086334	-0.037571
+4.390345	0.004788	0.004788	9.743755	0.048096	0.087133	-0.035573
+4.391314	-0.002394	0.031123	9.858669	0.047697	0.086334	-0.036905
+4.392331	0.002394	0.035911	9.806000	0.045299	0.087666	-0.035706
+4.393305	0.026334	0.009576	9.791636	0.047297	0.089265	-0.036505
+4.394284	0.004788	0.040699	9.798818	0.045698	0.090331	-0.034240
+4.395297	-0.043093	0.000000	9.794030	0.044632	0.089265	-0.033175
+4.396302	-0.014364	-0.021546	9.825152	0.043833	0.089398	-0.037038
+4.397300	0.009576	-0.050275	9.942460	0.045565	0.088998	-0.038371
+4.398301	-0.002394	0.016758	9.849093	0.046364	0.088199	-0.037438
+4.399330	0.028729	-0.047881	9.806000	0.045698	0.088466	-0.035173
+4.400329	0.016758	-0.059851	9.801212	0.044233	0.087799	-0.036639
+4.401264	0.007182	-0.043093	9.779666	0.045432	0.088998	-0.039703
+4.402289	0.011970	-0.038305	9.803606	0.046098	0.086467	-0.037571
+4.403264	0.014364	-0.057457	9.786848	0.045565	0.085268	-0.032775
+4.404251	-0.023940	-0.026334	9.782060	0.047697	0.087400	-0.035306
+4.405345	0.019152	0.007182	9.801212	0.046364	0.090597	-0.037571
+4.406344	0.050275	-0.028729	9.873033	0.046098	0.091263	-0.037305
+4.407344	0.035911	0.011970	9.853881	0.047297	0.089265	-0.035706
+4.408335	0.011970	0.031123	9.841911	0.047564	0.087799	-0.036372
+4.409304	-0.002394	-0.011970	9.777271	0.046897	0.086600	-0.037038
+4.410287	0.033517	0.014364	9.774877	0.047963	0.087133	-0.034640
+4.411344	-0.016758	0.062245	9.726997	0.047297	0.087533	-0.036505
+4.412344	0.011970	0.000000	9.746149	0.045565	0.085135	-0.037971
+4.413341	0.052669	-0.031123	9.806000	0.046098	0.087000	-0.035173
+4.414341	0.026334	-0.016758	9.803606	0.048230	0.089398	-0.034773
+4.415344	-0.019152	0.011970	9.875427	0.048763	0.088466	-0.038637
+4.416347	-0.014364	0.031123	9.846699	0.048629	0.087133	-0.037438
+4.417321	-0.038305	-0.021546	9.748543	0.046498	0.088332	-0.038104
+4.418305	-0.007182	-0.011970	9.844305	0.045032	0.088332	-0.035040
+4.419345	0.035911	-0.016758	9.808394	0.046364	0.086600	-0.033974
+4.420284	0.047881	-0.009576	9.827546	0.047164	0.087400	-0.035706
+4.421306	0.007182	0.031123	9.801212	0.046631	0.086600	-0.039037
+4.422244	-0.007182	0.052669	9.786848	0.048629	0.086201	-0.038637
+4.423344	0.000000	0.019152	9.789242	0.050495	0.086600	-0.035173
+4.424344	-0.038305	0.011970	9.806000	0.047830	0.087799	-0.035306
+4.425321	0.019152	0.040699	9.789242	0.045698	0.090331	-0.037305
+4.426345	-0.007182	0.055063	9.760513	0.044499	0.090064	-0.037172
+4.427345	-0.004788	0.009576	9.803606	0.046631	0.088332	-0.038237
+4.428312	-0.026334	-0.019152	9.772483	0.045432	0.089531	-0.038637
+4.429344	0.035911	0.014364	9.870639	0.044899	0.090198	-0.037438
+4.430346	0.000000	0.052669	9.885003	0.047830	0.089265	-0.034907
+4.431308	-0.028729	0.000000	9.798818	0.047031	0.087266	-0.034907
+4.432293	0.002394	-0.043093	9.798818	0.044899	0.087000	-0.032375
+4.433320	0.004788	-0.062245	9.710238	0.047963	0.087000	-0.035306
+4.434293	0.035911	0.002394	9.801212	0.049695	0.088199	-0.033974
+4.435256	0.026334	-0.011970	9.760513	0.047430	0.085401	-0.035706
+4.436344	0.035911	-0.002394	9.786848	0.045832	0.085934	-0.034907
+4.437313	0.045487	0.035911	9.784454	0.045698	0.085268	-0.034374
+4.438308	-0.021546	0.035911	9.760513	0.045032	0.086600	-0.035972
+4.439320	-0.043093	0.019152	9.779666	0.046897	0.086334	-0.037838
+4.440319	-0.028729	0.002394	9.753331	0.047830	0.084602	-0.036239
+4.441320	-0.011970	0.016758	9.782060	0.048763	0.084469	-0.037038
+4.442278	0.007182	-0.016758	9.738967	0.049828	0.086067	-0.037305
+4.443315	-0.081397	-0.016758	9.813182	0.049828	0.087799	-0.036505
+4.444319	-0.079003	-0.016758	9.813182	0.047697	0.086600	-0.038237
+4.445319	-0.033517	-0.019152	9.834729	0.045832	0.083936	-0.035706
+4.446315	-0.038305	-0.038305	9.779666	0.045698	0.085801	-0.034640
+4.447320	0.004788	-0.031123	9.853881	0.046498	0.088732	-0.036639
+4.448257	0.009576	0.002394	9.856275	0.047430	0.087266	-0.035173
+4.449261	-0.021546	0.002394	9.825152	0.047830	0.087666	-0.037971
+4.450319	-0.062245	0.000000	9.832334	0.048496	0.087933	-0.036239
+4.451321	-0.004788	-0.016758	9.772483	0.047430	0.088199	-0.038104
+4.452319	0.033517	-0.019152	9.789242	0.046631	0.085268	-0.038504
+4.453290	0.026334	-0.045487	9.810788	0.046364	0.083936	-0.035706
+4.454288	0.052669	-0.014364	9.849093	0.050761	0.085002	-0.034107
+4.455321	0.023940	0.000000	9.803606	0.049828	0.085668	-0.036905
+4.456319	-0.004788	-0.009576	9.786848	0.049162	0.087266	-0.037571
+4.457259	0.000000	0.026334	9.715026	0.047697	0.087400	-0.039303
+4.458314	0.026334	0.023940	9.729391	0.045965	0.089398	-0.035573
+4.459279	-0.055063	-0.016758	9.712632	0.046231	0.088599	-0.033441
+4.460293	-0.040699	0.004788	9.705450	0.046897	0.085268	-0.035173
+4.461321	0.019152	-0.028729	9.717420	0.046764	0.083936	-0.034374
+4.462320	0.000000	0.009576	9.755725	0.048230	0.086734	-0.033441
+4.463319	0.038305	0.016758	9.806000	0.049029	0.088466	-0.033841
+4.464281	0.021546	0.057457	9.837123	0.044632	0.087933	-0.036905
+4.465263	0.031123	0.052669	9.794030	0.046098	0.087133	-0.036772
+4.466321	0.021546	-0.014364	9.841911	0.047697	0.085934	-0.035040
+4.467279	0.016758	-0.040699	9.829940	0.046364	0.084335	-0.037305
+4.468282	-0.002394	-0.031123	9.741361	0.046764	0.087000	-0.036239
+4.469319	-0.019152	-0.031123	9.782060	0.045299	0.088332	-0.037305
+4.470292	0.000000	-0.031123	9.753331	0.047164	0.086867	-0.038504
+4.471267	0.035911	-0.033517	9.722208	0.047697	0.087000	-0.037305
+4.472244	0.055063	0.007182	9.743755	0.048629	0.086334	-0.036772
+4.473275	0.074215	0.043093	9.774877	0.045698	0.084469	-0.035306
+4.474319	0.035911	-0.002394	9.806000	0.046364	0.085668	-0.032908
+4.475270	0.014364	0.026334	9.851487	0.046631	0.087799	-0.037438
+4.476342	-0.002394	0.004788	9.841911	0.047963	0.087400	-0.036505
+4.477320	0.004788	-0.004788	9.932884	0.047963	0.087666	-0.034907
+4.478321	-0.023940	-0.033517	9.935278	0.048629	0.088599	-0.034240
+4.479317	-0.004788	-0.031123	9.779666	0.047031	0.088732	-0.034640
+4.480317	0.019152	-0.002394	9.777271	0.046498	0.088998	-0.034907
+4.481318	0.023940	0.026334	9.880215	0.047697	0.086467	-0.035306
+4.482289	0.011970	0.038305	9.827546	0.048496	0.087133	-0.034240
+4.483263	-0.047881	-0.009576	9.731785	0.046764	0.089265	-0.034773
+4.484271	0.009576	0.000000	9.755725	0.046098	0.086734	-0.035706
+4.485274	0.045487	0.007182	9.760513	0.045698	0.087400	-0.034773
+4.486280	-0.004788	0.007182	9.789242	0.047697	0.085801	-0.033574
+4.487317	0.045487	0.031123	9.815576	0.047164	0.087266	-0.033574
+4.488319	0.105338	0.031123	9.791636	0.046364	0.090730	-0.035706
+4.489314	0.081397	0.023940	9.748543	0.046098	0.090997	-0.037571
+4.490293	0.016758	0.031123	9.839517	0.047164	0.089798	-0.035706
+4.491256	-0.009576	-0.004788	9.863457	0.047430	0.090064	-0.036905
+4.492238	-0.014364	0.019152	9.813182	0.046631	0.087000	-0.037172
+4.493242	0.016758	0.014364	9.762907	0.043966	0.086467	-0.038637
+4.494243	0.033517	-0.021546	9.750937	0.045165	0.087000	-0.036505
+4.495243	-0.004788	-0.019152	9.839517	0.049695	0.090997	-0.038237
+4.496238	-0.021546	0.014364	9.798818	0.048629	0.090198	-0.036106
+4.497239	0.021546	0.019152	9.798818	0.045299	0.088466	-0.036372
+4.498238	0.023940	0.009576	9.873033	0.044632	0.088599	-0.034907
+4.499235	0.079003	-0.019152	9.841911	0.045432	0.086467	-0.036239
+4.500244	0.057457	-0.016758	9.810788	0.046897	0.085801	-0.037438
+4.501235	0.009576	0.007182	9.815576	0.048363	0.086734	-0.037838
+4.502236	0.016758	0.011970	9.846699	0.049429	0.087933	-0.038237
+4.503232	0.002394	0.031123	9.798818	0.050495	0.087400	-0.036505
+4.504235	-0.007182	-0.023940	9.815576	0.048496	0.087533	-0.034773
+4.505232	-0.007182	-0.014364	9.796424	0.045965	0.086467	-0.033175
+4.506235	0.031123	0.000000	9.827546	0.045698	0.087133	-0.033974
+4.507243	-0.026334	-0.014364	9.758119	0.047164	0.089398	-0.037971
+4.508216	-0.023940	-0.004788	9.719814	0.047430	0.088332	-0.039703
+4.509230	0.045487	-0.014364	9.782060	0.047963	0.087400	-0.037305
+4.510233	0.021546	0.000000	9.844305	0.046897	0.087533	-0.034240
+4.511229	-0.004788	-0.011970	9.741361	0.047430	0.088332	-0.033175
+4.512229	0.021546	0.004788	9.827546	0.050228	0.088466	-0.037038
+4.513214	0.021546	0.009576	9.837123	0.048096	0.086600	-0.036772
+4.514228	-0.019152	0.004788	9.827546	0.046897	0.084868	-0.033441
+4.515223	-0.031123	0.052669	9.791636	0.048363	0.087266	-0.034240
+4.516226	0.014364	0.004788	9.810788	0.048230	0.086067	-0.037172
+4.517230	0.028729	-0.071821	9.829940	0.046098	0.087000	-0.036905
+4.518226	-0.019152	-0.071821	9.806000	0.047297	0.086334	-0.036239
+4.519213	-0.014364	-0.002394	9.782060	0.046897	0.088466	-0.035173
+4.520206	-0.014364	0.011970	9.856275	0.048763	0.090464	-0.033308
+4.521231	0.004788	-0.016758	9.786848	0.048496	0.088998	-0.037038
+4.522220	-0.007182	-0.040699	9.762907	0.047564	0.089798	-0.039170
+4.523225	-0.031123	-0.004788	9.808394	0.044632	0.090198	-0.036372
+4.524223	-0.011970	0.038305	9.796424	0.045165	0.088332	-0.033041
+4.525224	0.004788	-0.009576	9.817970	0.045432	0.089931	-0.035040
+4.526230	0.033517	-0.047881	9.741361	0.046764	0.090331	-0.037305
+4.527230	0.004788	-0.069427	9.798818	0.047564	0.091130	-0.037305
+4.528239	-0.028729	-0.031123	9.707844	0.047164	0.092729	-0.036905
+4.529248	-0.083792	-0.011970	9.791636	0.042767	0.089665	-0.039037
+4.530245	-0.002394	0.071821	9.717420	0.043833	0.090064	-0.038371
+4.531241	0.007182	-0.014364	9.724603	0.046364	0.090730	-0.039703
+4.532325	-0.009576	0.011970	9.765301	0.048763	0.089398	-0.036106
+4.533267	-0.002394	0.009576	9.738967	0.049962	0.087400	-0.035306
+4.534261	-0.081397	0.023940	9.827546	0.048629	0.086067	-0.034374
+4.535219	-0.031123	0.011970	9.774877	0.046098	0.084069	-0.035040
+4.536261	0.026334	0.009576	9.762907	0.046897	0.087666	-0.038770
+4.537250	0.047881	-0.011970	9.770089	0.047297	0.090597	-0.039037
+4.538309	0.043093	-0.016758	9.770089	0.049162	0.088199	-0.036639
+4.539310	0.021546	-0.016758	9.777271	0.049562	0.087000	-0.036772
+4.540311	0.031123	-0.057457	9.753331	0.046897	0.087533	-0.034907
+4.541247	0.021546	-0.040699	9.808394	0.046364	0.087666	-0.034107
+4.542274	0.016758	0.021546	9.844305	0.048096	0.089665	-0.036106
+4.543271	-0.014364	0.038305	9.810788	0.048896	0.088599	-0.035972
+4.544314	0.047881	-0.019152	9.825152	0.048763	0.086867	-0.036239
+4.545308	0.007182	-0.038305	9.801212	0.048230	0.088332	-0.036239
+4.546315	-0.011970	-0.038305	9.767695	0.050095	0.089665	-0.035306
+4.547313	-0.007182	-0.019152	9.791636	0.048363	0.087799	-0.033041
+4.548313	-0.014364	-0.057457	9.791636	0.045432	0.088599	-0.034240
+4.549296	0.033517	-0.043093	9.841911	0.044632	0.087400	-0.035573
+4.550281	0.031123	0.016758	9.813182	0.043700	0.086067	-0.034507
+4.551312	0.028729	0.057457	9.779666	0.045698	0.086734	-0.034773
+4.552285	0.028729	0.050275	9.813182	0.047297	0.088998	-0.037704
+4.553304	0.033517	0.023940	9.856275	0.047430	0.089132	-0.035573
+4.554318	0.033517	-0.069427	9.798818	0.047164	0.088998	-0.033974
+4.555315	0.021546	-0.009576	9.801212	0.047031	0.088998	-0.035573
+4.556313	0.004788	0.021546	9.782060	0.046631	0.088199	-0.035040
+4.557307	0.033517	-0.038305	9.832334	0.046364	0.089665	-0.035972
+4.558280	0.028729	-0.004788	9.806000	0.047031	0.089798	-0.037172
+4.559313	-0.009576	-0.038305	9.808394	0.049828	0.090730	-0.036505
+4.560258	0.052669	-0.004788	9.767695	0.047830	0.088466	-0.034773
+4.561314	0.019152	0.011970	9.798818	0.046231	0.084868	-0.033041
+4.562307	-0.002394	-0.009576	9.808394	0.048629	0.085934	-0.035706
+4.563293	0.016758	-0.028729	9.849093	0.051028	0.087799	-0.037438
+4.564308	0.028729	-0.004788	9.863457	0.047430	0.087533	-0.037838
+4.565313	0.019152	-0.035911	9.834729	0.044899	0.086867	-0.036372
+4.566271	0.028729	0.007182	9.841911	0.046098	0.085135	-0.037305
+4.567311	-0.004788	0.000000	9.841911	0.047697	0.087799	-0.037438
+4.568313	0.055063	-0.031123	9.801212	0.047963	0.087933	-0.035972
+4.569316	0.009576	-0.040699	9.853881	0.047430	0.091663	-0.037971
+4.570312	-0.069427	-0.031123	9.762907	0.047963	0.090864	-0.040502
+4.571311	-0.059851	-0.023940	9.765301	0.047430	0.087933	-0.039570
+4.572295	-0.031123	-0.011970	9.782060	0.046631	0.087799	-0.037172
+4.573267	-0.009576	0.014364	9.784454	0.045565	0.086067	-0.036372
+4.574281	0.016758	0.016758	9.762907	0.047164	0.086334	-0.037838
+4.575313	-0.011970	-0.033517	9.798818	0.048629	0.087799	-0.034640
+4.576281	0.031123	-0.033517	9.789242	0.046631	0.088332	-0.034107
+4.577315	-0.035911	-0.021546	9.755725	0.044233	0.090198	-0.036639
+4.578315	-0.016758	-0.016758	9.755725	0.043433	0.090730	-0.034773
+4.579307	-0.062245	-0.043093	9.810788	0.045432	0.088332	-0.034107
+4.580313	0.007182	-0.031123	9.813182	0.045432	0.086867	-0.037038
+4.581310	-0.021546	0.002394	9.827546	0.047697	0.087799	-0.035306
+4.582312	0.014364	0.026334	9.817970	0.045965	0.086600	-0.038770
+4.583282	0.000000	0.016758	9.786848	0.045832	0.085401	-0.040502
+4.584300	-0.014364	-0.014364	9.774877	0.047830	0.083936	-0.039037
+4.585274	0.028729	-0.040699	9.801212	0.049029	0.084735	-0.035573
+4.586244	0.007182	-0.059851	9.772483	0.048629	0.086867	-0.037704
+4.587313	0.004788	-0.059851	9.803606	0.047031	0.086201	-0.040103
+4.588284	0.011970	0.009576	9.786848	0.045698	0.085668	-0.036772
+4.589313	0.050275	-0.026334	9.772483	0.045965	0.087933	-0.035706
+4.590314	0.040699	0.009576	9.782060	0.049828	0.090464	-0.036772
+4.591313	0.028729	0.081397	9.834729	0.049429	0.088199	-0.035173
+4.592314	-0.004788	-0.002394	9.798818	0.048896	0.086467	-0.035706
+4.593309	-0.033517	-0.045487	9.810788	0.048230	0.087533	-0.035440
+4.594271	0.007182	-0.004788	9.887397	0.049562	0.087933	-0.033841
+4.595311	0.009576	-0.045487	9.863457	0.048763	0.085002	-0.033974
+4.596311	0.016758	0.026334	9.822758	0.047164	0.084602	-0.033041
+4.597312	0.007182	0.026334	9.746149	0.045032	0.086201	-0.036905
+4.598254	0.011970	0.009576	9.762907	0.045165	0.087533	-0.035706
+4.599311	0.019152	-0.031123	9.813182	0.047430	0.088332	-0.035440
+4.600312	-0.007182	0.031123	9.858669	0.047830	0.089798	-0.036905
+4.601308	-0.021546	0.074215	9.894580	0.048629	0.088732	-0.035972
+4.602369	0.007182	0.040699	9.940066	0.047963	0.088732	-0.034107
+4.603276	0.055063	0.014364	9.920914	0.046231	0.084069	-0.032908
+4.604287	-0.011970	-0.035911	9.868245	0.047830	0.083936	-0.036239
+4.605274	-0.004788	-0.009576	9.885003	0.045965	0.085668	-0.040236
+4.606313	0.026334	-0.033517	9.827546	0.042900	0.088998	-0.038637
+4.607308	0.009576	0.035911	9.726997	0.044233	0.090597	-0.033974
+4.608309	0.033517	-0.002394	9.750937	0.045965	0.090997	-0.033708
+4.609310	-0.007182	-0.023940	9.777271	0.047564	0.088466	-0.033974
+4.610372	-0.047881	0.038305	9.741361	0.049162	0.087666	-0.034773
+4.611372	-0.002394	0.014364	9.784454	0.047164	0.088466	-0.039436
+4.612372	0.033517	-0.009576	9.841911	0.046897	0.087266	-0.041302
+4.613342	0.002394	-0.081397	9.820364	0.047430	0.088732	-0.036905
+4.614322	0.040699	-0.069427	9.861063	0.046364	0.087799	-0.033441
+4.615292	0.038305	-0.019152	9.834729	0.047297	0.086334	-0.035706
+4.616372	0.023940	0.011970	9.885003	0.048496	0.087000	-0.036372
+4.617374	0.016758	0.014364	9.801212	0.046498	0.085268	-0.039836
+4.618313	0.011970	0.002394	9.832334	0.047830	0.085668	-0.039436
+4.619307	0.033517	-0.002394	9.849093	0.047031	0.086867	-0.033841
+4.620291	-0.040699	-0.004788	9.798818	0.044499	0.088199	-0.034107
+4.621375	0.035911	0.021546	9.782060	0.045965	0.089132	-0.035440
+4.622376	0.019152	-0.033517	9.798818	0.048363	0.087533	-0.038904
+4.623273	0.033517	-0.019152	9.880215	0.048896	0.084735	-0.038504
+4.624359	0.033517	-0.062245	9.851487	0.047830	0.082870	-0.036905
+4.625313	0.004788	-0.057457	9.846699	0.046498	0.084069	-0.039303
+4.626383	-0.011970	0.014364	9.832334	0.045832	0.087400	-0.038770
+4.627373	0.002394	0.028729	9.815576	0.046897	0.089665	-0.039436
+4.628315	0.004788	0.007182	9.832334	0.046364	0.089931	-0.039436
+4.629371	0.007182	0.000000	9.774877	0.047830	0.090064	-0.036505
+4.630375	-0.038305	0.014364	9.765301	0.046897	0.090331	-0.036639
+4.631371	0.026334	-0.009576	9.738967	0.045432	0.089531	-0.037571
+4.632309	0.055063	-0.009576	9.782060	0.046098	0.087666	-0.035173
+4.633373	0.031123	-0.021546	9.786848	0.045165	0.090464	-0.033974
+4.634316	-0.009576	-0.011970	9.782060	0.044632	0.091263	-0.035173
+4.635288	0.014364	-0.028729	9.801212	0.045032	0.091263	-0.035573
+4.636371	0.019152	0.004788	9.784454	0.048230	0.089665	-0.038104
+4.637372	0.026334	0.059851	9.858669	0.049029	0.087533	-0.035706
+4.638338	-0.026334	-0.016758	9.796424	0.049962	0.087533	-0.037438
+4.639373	0.019152	-0.014364	9.820364	0.047430	0.086467	-0.035173
+4.640371	0.007182	-0.074215	9.822758	0.047164	0.086334	-0.033841
+4.641328	0.021546	-0.050275	9.868245	0.048629	0.086867	-0.038371
+4.642337	0.040699	-0.004788	9.789242	0.049429	0.086201	-0.037704
+4.643373	0.023940	-0.009576	9.767695	0.045965	0.087533	-0.033308
+4.644376	0.004788	0.007182	9.834729	0.046231	0.087133	-0.033041
+4.645372	-0.004788	-0.016758	9.803606	0.046498	0.086334	-0.036372
+4.646379	-0.009576	-0.040699	9.846699	0.045965	0.086067	-0.034640
+4.647373	-0.004788	-0.016758	9.868245	0.046631	0.085534	-0.037438
+4.648310	0.007182	0.000000	9.870639	0.049162	0.085534	-0.036372
+4.649290	0.004788	0.014364	9.767695	0.048896	0.087533	-0.036106
+4.650317	0.002394	-0.007182	9.755725	0.048629	0.087666	-0.036106
+4.651337	0.040699	0.021546	9.798818	0.046631	0.089798	-0.038770
+4.652383	0.009576	0.081397	9.837123	0.046364	0.089132	-0.039170
+4.653410	0.007182	0.031123	9.868245	0.046631	0.087666	-0.037038
+4.654319	-0.007182	-0.023940	9.779666	0.048496	0.089132	-0.034773
+4.655312	0.004788	-0.031123	9.803606	0.047830	0.090997	-0.034374
+4.656373	0.064639	0.016758	9.880215	0.046231	0.089398	-0.035839
+4.657373	0.045487	-0.011970	9.906550	0.046098	0.087533	-0.036372
+4.658327	0.011970	-0.011970	9.873033	0.047430	0.087000	-0.032242
+4.659295	-0.002394	-0.007182	9.954431	0.045565	0.089398	-0.034907
+4.660308	-0.023940	-0.009576	9.887397	0.044100	0.086867	-0.035972
+4.661308	-0.035911	0.011970	9.806000	0.044766	0.087000	-0.038371
+4.662287	0.031123	-0.055063	9.829940	0.045032	0.088732	-0.037971
+4.663369	0.045487	0.016758	9.801212	0.049429	0.087133	-0.033308
+4.664371	0.014364	0.035911	9.827546	0.047430	0.087266	-0.032242
+4.665372	-0.028729	-0.019152	9.796424	0.046364	0.086600	-0.035706
+4.666371	-0.052669	0.000000	9.760513	0.045698	0.084335	-0.037704
+4.667381	0.019152	-0.007182	9.760513	0.047564	0.089665	-0.036106
+4.668328	0.086186	-0.014364	9.760513	0.047297	0.090864	-0.035573
+4.669343	0.026334	-0.040699	9.815576	0.047830	0.087933	-0.032908
+4.670314	-0.076609	-0.035911	9.825152	0.046631	0.088199	-0.037305
+4.671312	-0.045487	-0.026334	9.870639	0.046631	0.089665	-0.036505
+4.672370	0.011970	0.007182	9.868245	0.046364	0.088865	-0.034107
+4.673314	0.004788	-0.016758	9.753331	0.046897	0.089398	-0.038904
+4.674309	-0.021546	-0.016758	9.726997	0.045432	0.091130	-0.038104
+4.675304	0.009576	-0.009576	9.815576	0.045832	0.090864	-0.037305
+4.676305	-0.019152	-0.059851	9.774877	0.046897	0.090064	-0.034773
+4.677305	-0.002394	-0.026334	9.789242	0.046231	0.088732	-0.034107
+4.678298	-0.021546	0.019152	9.885003	0.046098	0.086334	-0.033974
+4.679326	-0.009576	0.009576	9.858669	0.046098	0.084069	-0.033974
+4.680312	-0.035911	0.023940	9.772483	0.046364	0.088998	-0.037038
+4.681315	-0.014364	0.002394	9.777271	0.046498	0.091130	-0.038104
+4.682313	-0.002394	0.014364	9.801212	0.044632	0.088599	-0.035040
+4.683309	-0.035911	0.021546	9.762907	0.045832	0.087400	-0.035706
+4.684289	-0.021546	0.009576	9.779666	0.047164	0.085002	-0.037305
+4.685277	-0.028729	0.021546	9.817970	0.044899	0.086467	-0.035573
+4.686371	0.040699	-0.002394	9.791636	0.044632	0.087266	-0.034773
+4.687369	-0.002394	-0.059851	9.779666	0.044899	0.087266	-0.034640
+4.688325	-0.028729	-0.011970	9.760513	0.045965	0.088199	-0.033441
+4.689302	0.016758	-0.076609	9.777271	0.046364	0.087266	-0.037305
+4.690375	0.086186	-0.031123	9.789242	0.048629	0.088066	-0.038237
+4.691371	0.028729	0.000000	9.834729	0.048363	0.089398	-0.035306
+4.692369	0.014364	0.004788	9.803606	0.045432	0.089798	-0.034773
+4.693369	0.038305	0.038305	9.794030	0.045698	0.089931	-0.034507
+4.694328	0.038305	0.009576	9.786848	0.048096	0.090864	-0.031975
+4.695300	-0.040699	-0.016758	9.779666	0.047297	0.088865	-0.032775
+4.696298	-0.023940	-0.011970	9.774877	0.048230	0.084602	-0.035706
+4.697280	-0.007182	0.009576	9.791636	0.048096	0.083136	-0.037438
+4.698261	0.021546	0.026334	9.796424	0.050228	0.085268	-0.036106
+4.699278	0.000000	-0.007182	9.806000	0.047963	0.089398	-0.034240
+4.700273	0.000000	0.007182	9.762907	0.047430	0.090864	-0.033574
+4.701234	-0.009576	-0.009576	9.738967	0.045032	0.091930	-0.034374
+4.702280	0.019152	-0.007182	9.786848	0.045965	0.090864	-0.036639
+4.703280	0.067033	-0.014364	9.777271	0.046364	0.089132	-0.039436
+4.704280	-0.002394	0.016758	9.777271	0.047963	0.088599	-0.038770
+4.705259	-0.055063	-0.016758	9.810788	0.048096	0.087533	-0.038637
+4.706256	0.014364	-0.004788	9.858669	0.046764	0.089265	-0.038904
+4.707280	0.052669	0.023940	9.808394	0.045165	0.089265	-0.040902
+4.708278	-0.002394	-0.023940	9.755725	0.044499	0.088332	-0.038904
+4.709275	0.002394	-0.028729	9.779666	0.044766	0.085934	-0.033974
+4.710236	-0.007182	0.009576	9.820364	0.046764	0.086600	-0.034107
+4.711240	0.004788	-0.011970	9.810788	0.045832	0.087133	-0.035972
+4.712227	0.033517	-0.033517	9.777271	0.046897	0.088066	-0.036905
+4.713281	0.028729	0.014364	9.738967	0.046498	0.089265	-0.036905
+4.714275	-0.028729	0.002394	9.767695	0.046897	0.090730	-0.037971
+4.715272	-0.002394	0.002394	9.765301	0.047830	0.088199	-0.034374
+4.716273	-0.014364	0.021546	9.794030	0.048363	0.087933	-0.034640
+4.717273	0.026334	-0.045487	9.839517	0.048230	0.087666	-0.036106
+4.718270	-0.019152	-0.052669	9.779666	0.046897	0.087400	-0.039170
+4.719229	0.000000	-0.055063	9.789242	0.047164	0.087799	-0.035839
+4.720263	-0.019152	0.014364	9.832334	0.047830	0.088732	-0.035173
+4.721274	-0.019152	-0.055063	9.772483	0.047164	0.089265	-0.035972
+4.722273	-0.004788	-0.035911	9.722208	0.049296	0.089132	-0.033441
+4.723221	0.000000	-0.033517	9.784454	0.049562	0.086734	-0.032242
+4.724228	0.011970	-0.019152	9.765301	0.047564	0.086734	-0.035839
+4.725274	0.021546	-0.019152	9.750937	0.047830	0.086734	-0.038237
+4.726277	0.011970	0.047881	9.772483	0.047297	0.086600	-0.035173
+4.727272	0.057457	-0.011970	9.794030	0.046364	0.088998	-0.033841
+4.728272	0.047881	0.031123	9.789242	0.048496	0.090997	-0.030776
+4.729274	0.076609	-0.011970	9.762907	0.046098	0.088332	-0.033308
+4.730226	0.000000	0.000000	9.813182	0.046364	0.088865	-0.035440
+4.731273	-0.009576	0.026334	9.794030	0.045965	0.089265	-0.039436
+4.732272	0.023940	0.014364	9.806000	0.045432	0.086734	-0.039170
+4.733272	-0.081397	0.002394	9.772483	0.047697	0.086600	-0.037571
+4.734273	-0.050275	-0.009576	9.760513	0.047963	0.086734	-0.036772
+4.735271	-0.033517	-0.038305	9.794030	0.048230	0.087266	-0.035706
+4.736249	-0.002394	-0.047881	9.825152	0.050495	0.087933	-0.035706
+4.737255	0.043093	-0.055063	9.753331	0.049962	0.088998	-0.035040
+4.738313	0.026334	0.033517	9.808394	0.048896	0.088732	-0.033574
+4.739315	-0.004788	-0.045487	9.765301	0.047297	0.089398	-0.033041
+4.740316	0.047881	-0.011970	9.779666	0.048230	0.088599	-0.038904
+4.741315	0.016758	-0.019152	9.839517	0.046764	0.088599	-0.037438
+4.742318	0.000000	-0.033517	9.758119	0.047963	0.088066	-0.034240
+4.743315	0.035911	-0.040699	9.786848	0.047963	0.087933	-0.037838
+4.744315	0.000000	-0.079003	9.825152	0.048230	0.085002	-0.037038
+4.745303	0.033517	-0.038305	9.825152	0.047830	0.085534	-0.038637
+4.746316	0.038305	-0.014364	9.896974	0.045965	0.086600	-0.036106
+4.747281	-0.014364	0.000000	9.877821	0.044632	0.088199	-0.032508
+4.748246	-0.004788	0.033517	9.858669	0.044100	0.089531	-0.035839
+4.749276	0.000000	-0.016758	9.841911	0.045698	0.085135	-0.038371
+4.750318	-0.033517	0.011970	9.796424	0.047031	0.086334	-0.037172
+4.751240	0.028729	0.067033	9.671934	0.046364	0.090597	-0.035306
+4.752318	0.038305	0.021546	9.746149	0.044899	0.090064	-0.040236
+4.753318	0.045487	-0.033517	9.798818	0.043700	0.087799	-0.040636
+4.754317	0.040699	-0.019152	9.815576	0.046364	0.087400	-0.039436
+4.755315	0.031123	0.000000	9.841911	0.048896	0.087666	-0.035440
+4.756316	0.014364	0.007182	9.940066	0.050228	0.088865	-0.033041
+4.757287	0.019152	-0.028729	9.904156	0.048096	0.090064	-0.035040
+4.758279	0.021546	0.033517	9.815576	0.049695	0.088066	-0.033175
+4.759320	0.009576	-0.014364	9.772483	0.047963	0.087133	-0.035173
+4.760315	0.019152	-0.059851	9.772483	0.049695	0.088732	-0.037971
+4.761316	0.007182	-0.011970	9.806000	0.049429	0.090064	-0.037305
+4.762317	-0.021546	-0.067033	9.808394	0.044632	0.088066	-0.035440
+4.763314	-0.031123	-0.038305	9.717420	0.045299	0.085002	-0.038104
+4.764315	0.009576	0.026334	9.806000	0.049695	0.086334	-0.039170
+4.765315	0.069427	0.023940	9.796424	0.050894	0.088865	-0.037704
+4.766319	0.062245	0.000000	9.894580	0.048230	0.089132	-0.035306
+4.767260	0.031123	0.031123	9.839517	0.047297	0.086067	-0.037038
+4.768327	0.000000	-0.016758	9.767695	0.046631	0.085268	-0.035440
+4.769331	0.021546	0.023940	9.765301	0.045698	0.088199	-0.032908
+4.770319	-0.009576	-0.021546	9.736573	0.048496	0.089265	-0.029178
+4.771311	-0.007182	-0.043093	9.724603	0.052626	0.088199	-0.032375
+4.772284	0.000000	-0.050275	9.829940	0.049828	0.090864	-0.039303
+4.773250	0.004788	-0.028729	9.820364	0.047031	0.088732	-0.039170
+4.774320	0.069427	-0.026334	9.794030	0.045832	0.088865	-0.033441
+4.775315	-0.009576	0.002394	9.719814	0.044366	0.088466	-0.033708
+4.776321	-0.033517	-0.007182	9.822758	0.045032	0.087400	-0.036772
+4.777296	-0.031123	-0.035911	9.849093	0.046231	0.087133	-0.036239
+4.778248	0.026334	-0.009576	9.861063	0.047564	0.086600	-0.037838
+4.779319	0.062245	0.014364	9.844305	0.046764	0.087400	-0.036639
+4.780313	0.011970	0.033517	9.789242	0.045698	0.087933	-0.035839
+4.781318	0.050275	0.023940	9.791636	0.045832	0.089531	-0.038104
+4.782319	-0.004788	0.047881	9.770089	0.046498	0.089398	-0.037038
+4.783316	0.007182	0.004788	9.839517	0.048629	0.089265	-0.035972
+4.784311	-0.016758	-0.026334	9.851487	0.048629	0.089132	-0.036505
+4.785310	0.026334	-0.055063	9.803606	0.048096	0.087400	-0.037038
+4.786313	0.055063	-0.023940	9.806000	0.049162	0.087000	-0.035839
+4.787308	0.011970	-0.038305	9.808394	0.048629	0.087266	-0.034240
+4.788317	0.009576	-0.045487	9.770089	0.048230	0.086067	-0.033974
+4.789316	0.007182	-0.067033	9.803606	0.046764	0.088066	-0.032508
+4.790317	-0.007182	-0.019152	9.789242	0.045032	0.089132	-0.032908
+4.791317	0.021546	0.004788	9.810788	0.046364	0.087400	-0.034240
+4.792315	0.040699	0.004788	9.738967	0.047430	0.086600	-0.035706
+4.793320	0.021546	0.081397	9.669540	0.048230	0.086867	-0.036106
+4.794316	0.011970	0.021546	9.746149	0.046897	0.087000	-0.038104
+4.795318	-0.055063	-0.023940	9.758119	0.044366	0.086467	-0.038104
+4.796270	0.011970	-0.016758	9.832334	0.045032	0.087133	-0.037438
+4.797314	0.014364	-0.062245	9.849093	0.045698	0.087133	-0.036505
+4.798274	-0.011970	-0.019152	9.822758	0.046631	0.087133	-0.034107
+4.799315	-0.028729	0.050275	9.784454	0.046897	0.086467	-0.033308
+4.800311	-0.009576	0.014364	9.758119	0.048496	0.086467	-0.035972
+4.801311	0.079003	-0.021546	9.846699	0.047297	0.087000	-0.035573
+4.802319	0.050275	0.019152	9.815576	0.046897	0.088332	-0.035440
+4.803314	-0.007182	0.009576	9.779666	0.046498	0.088466	-0.035839
+4.804314	-0.021546	-0.016758	9.782060	0.046897	0.088998	-0.036905
+4.805293	-0.002394	-0.016758	9.882609	0.047963	0.088332	-0.036505
+4.806256	0.004788	0.002394	9.880215	0.045032	0.088865	-0.033308
+4.807217	0.059851	-0.011970	9.849093	0.044233	0.087933	-0.032775
+4.808223	0.045487	-0.035911	9.858669	0.046897	0.085135	-0.035972
+4.809307	0.057457	-0.038305	9.858669	0.048230	0.084735	-0.038237
+4.810317	0.016758	-0.043093	9.815576	0.047430	0.087133	-0.036239
+4.811250	-0.019152	0.000000	9.734179	0.045965	0.088199	-0.036372
+4.812315	-0.007182	0.000000	9.803606	0.047430	0.088998	-0.034640
+4.813317	0.009576	-0.031123	9.767695	0.048896	0.090864	-0.033441
+4.814317	0.011970	-0.007182	9.712632	0.049029	0.090331	-0.033841
+4.815315	0.000000	0.014364	9.765301	0.047697	0.088466	-0.040902
+4.816322	0.011970	0.014364	9.782060	0.047697	0.085934	-0.039836
+4.817295	0.016758	0.021546	9.784454	0.046764	0.087000	-0.036239
+4.818327	-0.021546	-0.047881	9.791636	0.044499	0.086867	-0.035573
+4.819368	0.021546	0.004788	9.798818	0.045698	0.085534	-0.038504
+4.820369	0.031123	-0.028729	9.782060	0.044366	0.086201	-0.033175
+4.821369	0.002394	-0.023940	9.808394	0.045965	0.085002	-0.035706
+4.822371	-0.019152	0.016758	9.817970	0.047430	0.084469	-0.037838
+4.823308	-0.019152	-0.019152	9.868245	0.046897	0.087400	-0.038104
+4.824302	-0.033517	-0.019152	9.806000	0.047697	0.088865	-0.036239
+4.825339	-0.014364	0.011970	9.710238	0.047697	0.089265	-0.035306
+4.826316	0.050275	-0.023940	9.820364	0.048629	0.090064	-0.033708
+4.827326	0.047881	-0.057457	9.765301	0.047830	0.090864	-0.031709
+4.828369	0.016758	-0.031123	9.762907	0.046764	0.089398	-0.035972
+4.829327	0.009576	0.028729	9.806000	0.045165	0.087533	-0.039303
+4.830376	0.028729	0.019152	9.820364	0.044899	0.088332	-0.037305
+4.831368	0.009576	-0.023940	9.815576	0.046498	0.086600	-0.033574
+4.832368	-0.011970	0.011970	9.849093	0.047164	0.088199	-0.032908
+4.833371	0.011970	0.023940	9.767695	0.048096	0.089531	-0.036106
+4.834324	0.038305	0.021546	9.731785	0.045965	0.087133	-0.034907
+4.835299	-0.023940	-0.016758	9.851487	0.044366	0.086867	-0.036106
+4.836351	-0.043093	-0.043093	9.829940	0.045832	0.089132	-0.038504
+4.837367	0.031123	0.011970	9.765301	0.046364	0.089665	-0.039037
+4.838373	0.100550	-0.002394	9.770089	0.045965	0.085801	-0.036505
+4.839371	-0.011970	0.000000	9.880215	0.045698	0.086334	-0.035706
+4.840371	0.021546	-0.019152	9.791636	0.046231	0.086734	-0.033308
+4.841370	-0.028729	0.021546	9.755725	0.046897	0.085801	-0.034773
+4.842370	-0.028729	-0.016758	9.873033	0.045698	0.085934	-0.039570
+4.843323	0.028729	-0.021546	9.837123	0.048496	0.084602	-0.038770
+4.844334	0.016758	-0.011970	9.774877	0.048230	0.085668	-0.035440
+4.845375	0.074215	-0.026334	9.729391	0.046231	0.086467	-0.035839
+4.846371	0.026334	-0.026334	9.880215	0.045299	0.087666	-0.033441
+4.847367	0.031123	-0.028729	9.796424	0.046098	0.087799	-0.034640
+4.848369	-0.019152	0.009576	9.746149	0.049029	0.085401	-0.038504
+4.849326	0.004788	0.000000	9.832334	0.050361	0.087533	-0.037038
+4.850327	-0.004788	-0.016758	9.877821	0.049828	0.088599	-0.037438
+4.851278	0.074215	-0.028729	9.774877	0.047963	0.089265	-0.039303
+4.852297	0.007182	-0.009576	9.796424	0.046498	0.087799	-0.034240
+4.853308	-0.016758	-0.038305	9.803606	0.046897	0.086600	-0.033974
+4.854362	0.009576	-0.045487	9.765301	0.047830	0.084469	-0.034773
+4.855368	-0.004788	-0.052669	9.741361	0.046231	0.086334	-0.036905
+4.856371	0.004788	-0.016758	9.806000	0.048363	0.087533	-0.036106
+4.857370	-0.021546	0.009576	9.786848	0.049029	0.089398	-0.034507
+4.858328	-0.016758	-0.079003	9.794030	0.047430	0.088865	-0.036639
+4.859368	0.031123	-0.009576	9.813182	0.045032	0.087133	-0.035306
+4.860368	0.011970	0.059851	9.817970	0.047031	0.088332	-0.033041
+4.861323	0.035911	0.023940	9.738967	0.046498	0.089931	-0.035440
+4.862314	-0.023940	-0.038305	9.806000	0.047430	0.090997	-0.036505
+4.863366	0.033517	0.002394	9.825152	0.047430	0.089398	-0.038904
+4.864369	0.009576	-0.055063	9.762907	0.046631	0.086600	-0.038770
+4.865367	-0.026334	-0.033517	9.870639	0.046764	0.088199	-0.035706
+4.866367	0.033517	-0.026334	9.868245	0.045965	0.087533	-0.032642
+4.867367	-0.031123	-0.057457	9.813182	0.047297	0.088332	-0.033974
+4.868326	-0.016758	-0.014364	9.794030	0.049029	0.089132	-0.037038
+4.869305	-0.009576	-0.002394	9.767695	0.048629	0.088865	-0.038104
+4.870306	0.023940	0.016758	9.758119	0.046364	0.086734	-0.036239
+4.871281	0.040699	-0.038305	9.762907	0.046764	0.086201	-0.036505
+4.872278	0.009576	-0.033517	9.726997	0.046364	0.085401	-0.034773
+4.873247	-0.014364	0.021546	9.724603	0.047564	0.085268	-0.037038
+4.874235	-0.055063	-0.007182	9.837123	0.049429	0.086334	-0.038104
+4.875226	-0.023940	-0.011970	9.846699	0.048896	0.089665	-0.039303
+4.876254	-0.004788	0.038305	9.753331	0.047031	0.089531	-0.038504
+4.877254	0.021546	0.023940	9.748543	0.047564	0.088865	-0.035972
+4.878255	-0.004788	0.011970	9.803606	0.046231	0.087933	-0.034107
+4.879253	0.026334	-0.004788	9.820364	0.047830	0.088865	-0.036639
+4.880250	-0.011970	-0.059851	9.846699	0.050095	0.086734	-0.037571
+4.881254	0.007182	-0.064639	9.861063	0.047830	0.086201	-0.035706
+4.882254	0.043093	-0.033517	9.798818	0.046897	0.086867	-0.035972
+4.883253	0.114914	-0.050275	9.707844	0.048629	0.087000	-0.039303
+4.884288	0.057457	-0.004788	9.750937	0.049695	0.088066	-0.035839
+4.885256	0.016758	-0.019152	9.822758	0.047830	0.088066	-0.033708
+4.886279	-0.059851	0.007182	9.853881	0.046364	0.089798	-0.035972
+4.887309	0.031123	-0.014364	9.856275	0.047830	0.090464	-0.037571
+4.888281	0.000000	-0.026334	9.806000	0.046364	0.090597	-0.035706
+4.889311	-0.009576	-0.019152	9.791636	0.045565	0.087400	-0.035306
+4.890308	-0.009576	0.011970	9.786848	0.047697	0.085135	-0.037038
+4.891306	-0.064639	-0.035911	9.774877	0.048896	0.086067	-0.036372
+4.892309	0.007182	-0.011970	9.820364	0.047564	0.088199	-0.036905
+4.893309	0.007182	-0.004788	9.722208	0.045299	0.087799	-0.036905
+4.894307	-0.033517	-0.057457	9.758119	0.044899	0.089132	-0.035706
+4.895277	0.000000	-0.016758	9.813182	0.047564	0.090331	-0.036106
+4.896294	-0.023940	-0.016758	9.767695	0.045965	0.088998	-0.035839
+4.897310	0.000000	0.023940	9.772483	0.044899	0.088066	-0.036505
+4.898262	-0.007182	0.011970	9.770089	0.045965	0.087933	-0.037704
+4.899309	0.016758	-0.019152	9.837123	0.047564	0.084735	-0.036372
+4.900302	-0.031123	-0.026334	9.820364	0.048763	0.082337	-0.035972
+4.901307	0.002394	0.016758	9.815576	0.047031	0.086467	-0.039969
+4.902340	0.000000	-0.007182	9.844305	0.044366	0.089265	-0.040636
+4.903330	0.009576	-0.007182	9.832334	0.046498	0.090198	-0.038371
+4.904330	0.028729	0.026334	9.784454	0.047164	0.087666	-0.035440
+4.905287	0.043093	-0.033517	9.803606	0.047164	0.083802	-0.037038
+4.906309	0.002394	-0.023940	9.851487	0.047697	0.085934	-0.035972
+4.907333	-0.023940	-0.050275	9.841911	0.046098	0.090997	-0.035972
+4.908331	0.004788	-0.050275	9.782060	0.047963	0.092329	-0.038904
+4.909330	0.040699	-0.038305	9.782060	0.048763	0.088998	-0.037704
+4.910298	-0.023940	0.043093	9.738967	0.046098	0.087533	-0.038904
+4.911329	-0.019152	0.021546	9.755725	0.044499	0.088466	-0.036106
+4.912330	0.076609	0.016758	9.837123	0.046764	0.088466	-0.035972
+4.913330	0.031123	0.007182	9.707844	0.046498	0.088199	-0.032375
+4.914288	-0.055063	0.007182	9.808394	0.047697	0.088732	-0.031709
+4.915288	-0.059851	-0.026334	9.738967	0.047430	0.085534	-0.034773
+4.916333	0.002394	-0.031123	9.755725	0.047830	0.085268	-0.037971
+4.917258	-0.009576	0.023940	9.813182	0.046498	0.085934	-0.033974
+4.918250	0.011970	-0.002394	9.803606	0.046098	0.086201	-0.033974
+4.919253	0.000000	-0.028729	9.846699	0.044366	0.082603	-0.033308
+4.920253	0.052669	0.028729	9.813182	0.047164	0.082470	-0.034773
+4.921241	0.043093	-0.011970	9.822758	0.047031	0.086467	-0.037704
+4.922233	0.026334	-0.033517	9.777271	0.047164	0.086201	-0.035972
+4.923219	0.026334	0.028729	9.746149	0.045299	0.084202	-0.037305
+4.924239	0.026334	0.031123	9.767695	0.044899	0.084602	-0.038904
+4.925217	-0.021546	-0.007182	9.808394	0.044499	0.085002	-0.034374
+4.926212	-0.038305	0.021546	9.767695	0.044499	0.087133	-0.034374
+4.927217	0.019152	0.057457	9.691086	0.047297	0.087133	-0.034240
+4.928216	0.047881	0.055063	9.801212	0.046098	0.087400	-0.032908
+4.929203	0.071821	0.035911	9.772483	0.046897	0.085934	-0.032242
+4.930242	-0.002394	0.028729	9.734179	0.046364	0.087933	-0.036372
+4.931236	0.007182	0.038305	9.813182	0.046364	0.088865	-0.036905
+4.932240	0.035911	0.021546	9.755725	0.044766	0.086867	-0.036372
+4.933242	0.033517	-0.035911	9.829940	0.046231	0.086067	-0.034240
+4.934245	0.021546	-0.028729	9.856275	0.044766	0.086067	-0.031975
+4.935241	0.035911	-0.055063	9.892186	0.045965	0.087799	-0.033841
+4.936241	-0.011970	-0.052669	9.755725	0.048496	0.090198	-0.037305
+4.937237	-0.009576	-0.026334	9.815576	0.049296	0.089798	-0.036639
+4.938242	-0.045487	-0.002394	9.870639	0.047963	0.087799	-0.035040
+4.939241	0.002394	0.002394	9.841911	0.047164	0.088466	-0.035306
+4.940239	0.021546	-0.033517	9.789242	0.045032	0.088599	-0.038504
+4.941241	0.050275	-0.023940	9.861063	0.046764	0.087000	-0.037704
+4.942240	0.035911	0.000000	9.748543	0.046498	0.086334	-0.033841
+4.943242	0.004788	0.028729	9.734179	0.047430	0.089665	-0.034240
+4.944234	-0.009576	0.014364	9.760513	0.048096	0.090597	-0.038637
+4.945217	-0.031123	-0.011970	9.858669	0.048896	0.088865	-0.038104
+4.946236	-0.021546	-0.026334	9.841911	0.047031	0.088199	-0.036905
+4.947212	0.040699	0.007182	9.784454	0.045432	0.090997	-0.033041
+4.948242	0.035911	0.002394	9.758119	0.046364	0.090864	-0.034640
+4.949240	0.047881	-0.004788	9.789242	0.048896	0.088599	-0.038237
+4.950295	0.045487	0.011970	9.813182	0.048629	0.088466	-0.040502
+4.951273	-0.011970	-0.057457	9.849093	0.049429	0.088066	-0.038637
+4.952329	-0.035911	-0.023940	9.904156	0.047430	0.088066	-0.034374
+4.953330	-0.014364	-0.016758	9.918520	0.045832	0.089265	-0.036505
+4.954301	0.035911	-0.004788	9.858669	0.045165	0.089931	-0.038237
+4.955326	0.028729	0.023940	9.873033	0.045698	0.089132	-0.035839
+4.956330	0.035911	0.002394	9.837123	0.045965	0.087266	-0.035173
+4.957330	0.007182	0.033517	9.870639	0.048896	0.086734	-0.036505
+4.958244	0.004788	-0.028729	9.834729	0.049429	0.087533	-0.035306
+4.959307	0.002394	-0.007182	9.777271	0.047031	0.090864	-0.038104
+4.960285	0.050275	-0.011970	9.760513	0.043833	0.088865	-0.037172
+4.961303	0.011970	-0.038305	9.717420	0.042900	0.088599	-0.038904
+4.962327	0.021546	0.031123	9.712632	0.046364	0.088865	-0.037704
+4.963329	0.074215	0.047881	9.767695	0.046364	0.087666	-0.035173
+4.964329	-0.023940	-0.002394	9.827546	0.044366	0.087799	-0.035173
+4.965293	0.004788	0.016758	9.829940	0.045165	0.089798	-0.038371
+4.966252	0.019152	-0.031123	9.868245	0.046231	0.088466	-0.036905
+4.967330	0.038305	0.004788	9.870639	0.046897	0.089665	-0.037305
+4.968265	0.033517	0.019152	9.887397	0.045432	0.091263	-0.035839
+4.969329	0.019152	0.043093	9.839517	0.045032	0.091530	-0.033441
+4.970329	0.000000	0.026334	9.810788	0.045299	0.088732	-0.034773
+4.971324	0.000000	0.009576	9.841911	0.046631	0.086467	-0.033574
+4.972326	-0.026334	0.021546	9.865851	0.049162	0.083403	-0.034773
+4.973330	-0.031123	-0.004788	9.829940	0.045965	0.083270	-0.035706
+4.974283	-0.035911	-0.035911	9.829940	0.045565	0.087533	-0.034773
+4.975292	0.033517	-0.021546	9.750937	0.046764	0.087933	-0.036505
+4.976269	0.019152	0.009576	9.726997	0.047164	0.087799	-0.036772
+4.977252	0.026334	-0.011970	9.782060	0.048763	0.088998	-0.034773
+4.978332	0.000000	0.031123	9.801212	0.047430	0.088066	-0.037038
+4.979328	0.026334	0.028729	9.715026	0.047430	0.086867	-0.034773
+4.980325	0.007182	-0.028729	9.703056	0.046364	0.085268	-0.032242
+4.981329	0.038305	-0.004788	9.827546	0.045165	0.086734	-0.036106
+4.982332	0.031123	0.004788	9.868245	0.047031	0.088066	-0.035839
+4.983257	0.033517	-0.002394	9.868245	0.047031	0.087666	-0.034507
+4.984284	0.014364	0.007182	9.865851	0.047697	0.087666	-0.038504
+4.985230	0.021546	-0.052669	9.772483	0.047564	0.086467	-0.036772
+4.986265	-0.035911	-0.064639	9.834729	0.046498	0.087133	-0.037172
+4.987262	-0.083792	-0.031123	9.815576	0.047031	0.087799	-0.037172
+4.988260	0.007182	-0.031123	9.861063	0.045698	0.087400	-0.038237
+4.989260	-0.014364	-0.040699	9.889792	0.046364	0.084868	-0.038237
+4.990329	-0.014364	0.004788	9.815576	0.045698	0.085002	-0.036772
+4.991330	0.031123	-0.002394	9.865851	0.045165	0.085534	-0.036639
+4.992328	0.062245	0.011970	9.885003	0.046364	0.085534	-0.036639
+4.993330	0.009576	-0.002394	9.882609	0.047564	0.086067	-0.031975
+4.994330	-0.009576	0.028729	9.817970	0.046897	0.086600	-0.031842
+4.995258	-0.007182	0.004788	9.782060	0.046231	0.086201	-0.036505
+4.996292	-0.011970	-0.004788	9.705450	0.047297	0.084868	-0.035573
+4.997330	-0.033517	0.023940	9.738967	0.047031	0.085268	-0.034507
+4.998255	-0.011970	-0.033517	9.750937	0.046364	0.088332	-0.035440
+4.999230	0.011970	0.000000	9.856275	0.046098	0.088466	-0.038637
+5.000229	0.019152	-0.002394	9.841911	0.049429	0.088066	-0.037838
+5.001224	0.021546	0.007182	9.748543	0.051960	0.087933	-0.038104
+5.002225	0.045487	-0.026334	9.729391	0.048230	0.086867	-0.036772
+5.003228	0.040699	-0.045487	9.659963	0.043567	0.087666	-0.034507
+5.004260	0.028729	-0.004788	9.770089	0.044499	0.089265	-0.036505
+5.005231	-0.019152	0.019152	9.798818	0.046631	0.088066	-0.036505
+5.006224	-0.052669	0.035911	9.841911	0.045432	0.087266	-0.036372
+5.007229	0.007182	0.007182	9.803606	0.045698	0.087799	-0.039037
+5.008208	0.045487	0.002394	9.762907	0.046498	0.087533	-0.037704
+5.009244	-0.009576	-0.023940	9.841911	0.045432	0.088732	-0.036905
+5.010237	0.019152	-0.002394	9.832334	0.047564	0.087533	-0.036372
+5.011242	0.038305	0.002394	9.765301	0.047297	0.087799	-0.035306
+5.012240	0.023940	0.009576	9.820364	0.044233	0.087400	-0.036239
+5.013239	0.011970	0.040699	9.741361	0.043567	0.087799	-0.039969
+5.014242	0.007182	0.023940	9.806000	0.045832	0.089665	-0.036905
+5.015240	0.026334	0.019152	9.789242	0.048896	0.089531	-0.035306
+5.016234	0.059851	0.014364	9.734179	0.047830	0.086600	-0.034907
+5.017252	0.016758	0.002394	9.794030	0.047430	0.084868	-0.035173
+5.018226	-0.038305	-0.026334	9.731785	0.046764	0.085801	-0.035573
+5.019229	-0.014364	0.009576	9.762907	0.044899	0.085668	-0.039170
+5.020238	-0.002394	0.052669	9.806000	0.048629	0.088466	-0.035306
+5.021233	0.002394	0.002394	9.755725	0.050495	0.090198	-0.036505
+5.022217	0.004788	0.021546	9.748543	0.048363	0.090730	-0.039170
+5.023260	-0.007182	0.000000	9.758119	0.047164	0.089665	-0.036239
+5.024258	0.011970	-0.021546	9.832334	0.044366	0.087400	-0.035573
+5.025258	-0.009576	-0.019152	9.810788	0.044100	0.088599	-0.036239
+5.026258	0.004788	0.026334	9.822758	0.045032	0.088865	-0.035706
+5.027257	-0.011970	0.019152	9.810788	0.048496	0.089531	-0.037438
+5.028257	-0.028729	0.055063	9.896974	0.047031	0.087533	-0.036772
+5.029256	-0.004788	-0.002394	9.858669	0.045832	0.087000	-0.036639
+5.030221	0.035911	-0.038305	9.856275	0.048363	0.085934	-0.036372
+5.031215	-0.002394	-0.004788	9.853881	0.046897	0.089132	-0.036239
+5.032235	0.031123	-0.002394	9.832334	0.046098	0.087933	-0.039703
+5.033227	0.035911	-0.031123	9.832334	0.046897	0.087933	-0.040103
+5.034253	-0.019152	0.002394	9.798818	0.048230	0.085135	-0.037438
+5.035252	0.016758	0.016758	9.863457	0.049828	0.083270	-0.038104
+5.036242	0.016758	0.007182	9.858669	0.048230	0.084735	-0.037172
+5.037234	0.011970	0.019152	9.686298	0.048096	0.087266	-0.033974
+5.038231	-0.014364	-0.014364	9.825152	0.047564	0.087933	-0.036372
+5.039244	0.014364	-0.011970	9.796424	0.048763	0.088865	-0.037838
+5.040236	0.016758	-0.031123	9.762907	0.048230	0.088332	-0.035839
+5.041235	0.047881	-0.026334	9.777271	0.047430	0.087666	-0.035440
+5.042241	-0.023940	-0.016758	9.779666	0.047697	0.086600	-0.035706
+5.043249	-0.019152	-0.028729	9.760513	0.047164	0.087933	-0.037305
+5.044218	0.047881	-0.023940	9.765301	0.046231	0.090730	-0.036772
+5.045236	0.007182	-0.011970	9.789242	0.046764	0.090464	-0.038904
+5.046251	-0.004788	-0.023940	9.806000	0.046364	0.087400	-0.037838
+5.047252	-0.004788	-0.023940	9.806000	0.046498	0.085801	-0.036505
+5.048251	-0.004788	-0.007182	9.825152	0.047164	0.088865	-0.034107
+5.049256	0.055063	-0.043093	9.765301	0.048363	0.089665	-0.033974
+5.050305	-0.014364	-0.055063	9.683904	0.047297	0.088066	-0.037172
+5.051271	-0.019152	-0.019152	9.791636	0.045832	0.087266	-0.036372
+5.052303	-0.026334	0.000000	9.758119	0.045832	0.087400	-0.037704
+5.053302	0.002394	0.002394	9.841911	0.047031	0.087266	-0.038504
+5.054302	-0.002394	-0.028729	9.820364	0.047830	0.087666	-0.039303
+5.055304	-0.004788	0.002394	9.794030	0.046631	0.087000	-0.036772
+5.056301	0.019152	0.014364	9.762907	0.045565	0.084868	-0.034907
+5.057304	0.009576	-0.038305	9.758119	0.046764	0.086734	-0.034374
+5.058298	-0.016758	-0.019152	9.724603	0.048096	0.087799	-0.034507
+5.059301	-0.062245	-0.021546	9.693480	0.048230	0.088332	-0.032242
+5.060303	-0.016758	-0.021546	9.827546	0.047830	0.087533	-0.033708
+5.061303	0.009576	-0.021546	9.825152	0.046231	0.084335	-0.035306
+5.062301	0.031123	-0.007182	9.803606	0.045832	0.085801	-0.036239
+5.063293	0.023940	-0.021546	9.839517	0.046498	0.089132	-0.033574
+5.064269	-0.021546	-0.016758	9.777271	0.047830	0.090331	-0.033175
+5.065302	0.007182	0.004788	9.806000	0.049828	0.088732	-0.035706
+5.066274	0.007182	0.007182	9.750937	0.050495	0.086734	-0.037838
+5.067301	-0.004788	-0.011970	9.808394	0.049429	0.085801	-0.036772
+5.068251	-0.014364	0.014364	9.817970	0.046498	0.084868	-0.037704
+5.069300	-0.021546	-0.009576	9.806000	0.046631	0.084335	-0.036505
+5.070297	-0.002394	-0.016758	9.844305	0.047031	0.089132	-0.036239
+5.071302	0.016758	-0.074215	9.810788	0.047963	0.089132	-0.040636
+5.072301	0.071821	-0.043093	9.746149	0.046764	0.089798	-0.038237
+5.073302	0.033517	-0.014364	9.829940	0.045698	0.089665	-0.036239
+5.074274	0.038305	-0.004788	9.834729	0.045965	0.088466	-0.034773
+5.075241	0.019152	0.002394	9.882609	0.046631	0.088066	-0.035972
+5.076237	0.045487	-0.023940	9.834729	0.047564	0.087799	-0.038637
+5.077223	0.055063	-0.009576	9.767695	0.045965	0.087799	-0.037838
+5.078251	0.052669	-0.011970	9.767695	0.043300	0.087799	-0.036106
+5.079230	-0.004788	-0.019152	9.858669	0.044100	0.088732	-0.036239
+5.080216	0.028729	-0.057457	9.844305	0.045165	0.092462	-0.036372
+5.081224	0.014364	-0.028729	9.875427	0.046364	0.092729	-0.037305
+5.082198	0.002394	0.000000	9.832334	0.048230	0.090464	-0.036505
+5.083214	0.028729	-0.040699	9.779666	0.047430	0.088599	-0.036905
+5.084228	0.064639	-0.023940	9.791636	0.044366	0.086734	-0.036505
+5.085238	0.019152	-0.031123	9.817970	0.044499	0.086334	-0.039836
+5.086271	0.050275	-0.009576	9.849093	0.044632	0.087266	-0.036505
+5.087261	0.040699	-0.009576	9.786848	0.044766	0.087400	-0.034773
+5.088237	0.050275	-0.021546	9.782060	0.045432	0.089132	-0.033708
+5.089238	-0.035911	-0.009576	9.834729	0.044499	0.090331	-0.033441
+5.090233	-0.007182	0.009576	9.746149	0.048230	0.087000	-0.036772
+5.091238	0.050275	-0.014364	9.825152	0.049029	0.084868	-0.036905
+5.092260	-0.026334	-0.009576	9.806000	0.048763	0.085401	-0.033574
+5.093261	0.052669	0.023940	9.803606	0.048230	0.086734	-0.033974
+5.094233	0.035911	-0.038305	9.765301	0.048763	0.088199	-0.035839
+5.095267	-0.040699	-0.055063	9.786848	0.049162	0.086734	-0.036905
+5.096261	-0.055063	0.000000	9.808394	0.049296	0.087133	-0.037172
+5.097262	-0.002394	-0.057457	9.722208	0.046231	0.087533	-0.035573
+5.098238	0.011970	0.004788	9.755725	0.046498	0.088199	-0.037438
+5.099261	-0.011970	0.035911	9.734179	0.046764	0.090198	-0.036639
+5.100262	-0.014364	0.016758	9.789242	0.046897	0.090730	-0.035972
+5.101238	-0.011970	-0.059851	9.813182	0.045565	0.086067	-0.037305
+5.102271	0.026334	-0.038305	9.806000	0.044499	0.084469	-0.036639
+5.103232	0.026334	-0.059851	9.839517	0.046098	0.087266	-0.037038
+5.104237	0.016758	-0.043093	9.808394	0.046897	0.089132	-0.037838
+5.105238	-0.014364	-0.028729	9.853881	0.048230	0.089931	-0.035706
+5.106244	-0.038305	-0.016758	9.868245	0.047963	0.087400	-0.036905
+5.107317	-0.014364	0.031123	9.770089	0.047564	0.086201	-0.037305
+5.108277	0.055063	0.000000	9.820364	0.046897	0.086067	-0.037438
+5.109314	0.014364	-0.016758	9.863457	0.047164	0.087799	-0.034640
+5.110282	-0.011970	-0.011970	9.734179	0.045432	0.087133	-0.035040
+5.111314	0.040699	0.000000	9.674328	0.047430	0.087533	-0.037971
+5.112312	0.014364	0.057457	9.746149	0.048763	0.088998	-0.036772
+5.113315	-0.004788	0.031123	9.825152	0.045299	0.087799	-0.036772
+5.114314	0.035911	0.004788	9.796424	0.045165	0.088732	-0.036372
+5.115244	0.023940	0.028729	9.748543	0.043700	0.090730	-0.036772
+5.116220	0.004788	0.023940	9.837123	0.044233	0.088998	-0.036639
+5.117307	0.002394	0.040699	9.765301	0.045832	0.087400	-0.036372
+5.118283	-0.019152	0.023940	9.806000	0.044499	0.088732	-0.036372
+5.119314	0.062245	-0.009576	9.796424	0.045299	0.090331	-0.037172
+5.120311	0.059851	-0.033517	9.815576	0.046231	0.089665	-0.034507
+5.121314	0.021546	0.000000	9.925702	0.046364	0.087666	-0.035839
+5.122314	-0.023940	0.016758	9.928096	0.046498	0.086467	-0.039037
+5.123259	-0.021546	0.016758	9.832334	0.047830	0.086600	-0.039170
+5.124255	0.014364	0.016758	9.820364	0.047830	0.089531	-0.036505
+5.125281	0.016758	0.019152	9.841911	0.045965	0.089531	-0.035173
+5.126259	0.014364	-0.004788	9.839517	0.045299	0.087799	-0.038104
+5.127305	0.009576	-0.038305	9.817970	0.048230	0.088732	-0.042634
+5.128257	-0.028729	-0.052669	9.736573	0.045032	0.087799	-0.037305
+5.129315	-0.045487	-0.004788	9.741361	0.045165	0.085801	-0.032375
+5.130317	-0.021546	0.000000	9.820364	0.045965	0.086734	-0.035306
+5.131314	0.043093	-0.004788	9.770089	0.047697	0.089798	-0.035839
+5.132313	0.031123	-0.004788	9.779666	0.047697	0.088599	-0.036905
+5.133313	0.057457	0.000000	9.817970	0.045565	0.086734	-0.036106
+5.134314	0.028729	-0.023940	9.817970	0.047297	0.085401	-0.037438
+5.135300	-0.023940	0.011970	9.777271	0.048096	0.084469	-0.036372
+5.136280	-0.009576	0.023940	9.681510	0.049029	0.085268	-0.037305
+5.137316	0.026334	0.033517	9.731785	0.047297	0.087666	-0.036639
+5.138314	-0.004788	-0.014364	9.798818	0.045565	0.086067	-0.035573
+5.139314	-0.028729	-0.007182	9.760513	0.044632	0.085801	-0.036772
+5.140313	0.023940	-0.004788	9.813182	0.047564	0.087000	-0.038637
+5.141246	0.043093	-0.011970	9.844305	0.049562	0.089798	-0.035173
+5.142258	-0.016758	-0.040699	9.808394	0.049296	0.088199	-0.034240
+5.143312	0.019152	-0.021546	9.849093	0.046498	0.083802	-0.036639
+5.144312	0.028729	0.028729	9.803606	0.046231	0.086067	-0.035040
+5.145311	0.011970	0.031123	9.820364	0.047564	0.087666	-0.032642
+5.146292	0.040699	-0.028729	9.825152	0.047697	0.089531	-0.032508
+5.147315	-0.016758	-0.047881	9.863457	0.048763	0.089931	-0.035440
+5.148253	0.050275	-0.026334	9.822758	0.047430	0.089531	-0.034374
+5.149314	0.009576	0.009576	9.782060	0.045698	0.088732	-0.036239
+5.150311	-0.011970	0.004788	9.741361	0.045832	0.089265	-0.035040
+5.151307	0.023940	-0.007182	9.717420	0.047031	0.090331	-0.035306
+5.152312	0.007182	-0.033517	9.710238	0.048363	0.088998	-0.035839
+5.153313	0.043093	-0.028729	9.779666	0.049962	0.089531	-0.037571
+5.154314	-0.016758	-0.002394	9.839517	0.049162	0.088066	-0.035440
+5.155296	-0.002394	-0.026334	9.827546	0.046098	0.087133	-0.038504
+5.156289	0.002394	0.011970	9.774877	0.047164	0.085934	-0.039570
+5.157256	0.014364	-0.026334	9.741361	0.046897	0.086600	-0.035173
+5.158315	-0.007182	0.019152	9.810788	0.047830	0.087666	-0.037704
+5.159314	0.043093	0.011970	9.863457	0.048629	0.090464	-0.038104
+5.160307	0.000000	-0.031123	9.777271	0.050628	0.090864	-0.035440
+5.161260	0.033517	-0.009576	9.717420	0.050361	0.089531	-0.040769
+5.162314	0.009576	-0.023940	9.674328	0.045432	0.088998	-0.039436
+5.163310	0.002394	0.000000	9.736573	0.043833	0.088066	-0.037571
+5.164306	-0.040699	-0.052669	9.820364	0.045032	0.086334	-0.036639
+5.165283	0.050275	0.023940	9.746149	0.046764	0.084069	-0.035706
+5.166297	0.050275	-0.007182	9.782060	0.048096	0.086201	-0.035573
+5.167313	0.019152	0.026334	9.853881	0.048896	0.088066	-0.034773
+5.168313	-0.019152	0.040699	9.911338	0.047830	0.088332	-0.036239
+5.169313	-0.021546	0.028729	9.791636	0.048629	0.089265	-0.037838
+5.170313	0.052669	0.007182	9.738967	0.048629	0.089665	-0.038504
+5.171312	0.026334	0.026334	9.734179	0.045032	0.088732	-0.039170
+5.172314	0.043093	0.009576	9.719814	0.044766	0.088332	-0.037038
+5.173307	-0.023940	0.019152	9.801212	0.044899	0.087799	-0.036772
+5.174251	-0.045487	0.031123	9.705450	0.047430	0.085801	-0.034640
+5.175279	-0.016758	-0.004788	9.798818	0.047963	0.085934	-0.036505
+5.176260	0.009576	-0.016758	9.875427	0.048496	0.085268	-0.035839
+5.177341	-0.031123	-0.026334	9.801212	0.047430	0.087266	-0.033441
+5.178282	0.000000	-0.011970	9.753331	0.044366	0.087666	-0.037038
+5.179312	-0.004788	-0.040699	9.750937	0.045299	0.088066	-0.038504
+5.180314	-0.004788	-0.043093	9.851487	0.047697	0.085135	-0.036372
+5.181311	0.016758	-0.031123	9.841911	0.046231	0.085268	-0.033308
+5.182278	0.021546	-0.014364	9.846699	0.047031	0.086201	-0.033708
+5.183313	-0.016758	0.000000	9.786848	0.048896	0.089531	-0.035173
+5.184312	0.004788	-0.026334	9.760513	0.047697	0.088199	-0.037704
+5.185256	0.000000	-0.014364	9.801212	0.046498	0.087000	-0.037838
+5.186270	-0.014364	-0.052669	9.817970	0.045565	0.085135	-0.035440
+5.187306	-0.021546	-0.055063	9.839517	0.046364	0.088466	-0.036772
+5.188307	-0.014364	-0.021546	9.815576	0.046364	0.090064	-0.038504
+5.189313	0.016758	-0.019152	9.729391	0.045165	0.086467	-0.034773
+5.190313	-0.007182	0.047881	9.839517	0.047164	0.086334	-0.033708
+5.191311	0.021546	-0.038305	9.880215	0.050228	0.085934	-0.036772
+5.192313	0.002394	0.000000	9.839517	0.047697	0.087000	-0.038371
+5.193315	0.021546	-0.040699	9.748543	0.047564	0.087266	-0.035839
+5.194313	0.014364	-0.009576	9.813182	0.048496	0.089531	-0.034240
+5.195280	-0.026334	0.014364	9.839517	0.048096	0.086600	-0.034640
+5.196270	0.000000	-0.007182	9.851487	0.046897	0.083669	-0.036106
+5.197339	-0.019152	-0.002394	9.798818	0.046098	0.084735	-0.035306
+5.198315	0.043093	0.016758	9.829940	0.044100	0.087266	-0.035839
+5.199274	0.064639	-0.002394	9.767695	0.046897	0.087933	-0.032508
+5.200312	0.019152	0.000000	9.808394	0.047697	0.087266	-0.034507
+5.201253	0.004788	-0.016758	9.789242	0.047164	0.088998	-0.037305
+5.202313	0.009576	0.033517	9.834729	0.047697	0.089798	-0.037971
+5.203315	0.021546	0.009576	9.832334	0.047164	0.087666	-0.037838
+5.204312	0.009576	-0.047881	9.777271	0.044632	0.087799	-0.037971
+5.205309	-0.009576	-0.047881	9.794030	0.045032	0.088066	-0.037305
+5.206271	-0.026334	-0.019152	9.815576	0.047697	0.087933	-0.037172
+5.207314	0.033517	-0.026334	9.849093	0.051028	0.087000	-0.039703
+5.208307	0.028729	-0.052669	9.798818	0.049162	0.089531	-0.038371
+5.209276	-0.016758	0.011970	9.865851	0.047963	0.088066	-0.035306
+5.210256	-0.019152	0.014364	9.794030	0.048363	0.087400	-0.037971
+5.211313	0.028729	0.009576	9.820364	0.047297	0.087000	-0.037838
+5.212313	0.031123	-0.069427	9.806000	0.046098	0.086734	-0.036239
+5.213309	-0.011970	-0.047881	9.796424	0.044899	0.087799	-0.035706
+5.214315	0.028729	0.000000	9.877821	0.046897	0.088865	-0.037038
+5.215314	0.069427	-0.004788	9.832334	0.048363	0.088199	-0.033041
+5.216287	0.028729	0.000000	9.810788	0.048629	0.087133	-0.033708
+5.217258	0.007182	0.004788	9.815576	0.048896	0.088466	-0.033841
+5.218247	0.023940	0.004788	9.827546	0.047564	0.090730	-0.030776
+5.219315	-0.019152	-0.011970	9.772483	0.048096	0.089265	-0.032908
+5.220311	-0.009576	-0.026334	9.770089	0.046231	0.087266	-0.034640
+5.221306	0.031123	-0.009576	9.904156	0.046364	0.086734	-0.035306
+5.222266	0.016758	0.057457	9.815576	0.044632	0.087799	-0.036905
+5.223310	0.035911	-0.014364	9.813182	0.046231	0.087000	-0.035706
+5.224250	0.057457	-0.062245	9.774877	0.047297	0.088066	-0.037038
+5.225282	-0.007182	-0.026334	9.676722	0.049296	0.090597	-0.037305
+5.226277	0.004788	0.016758	9.693480	0.048896	0.090864	-0.034907
+5.227286	0.050275	0.033517	9.870639	0.046098	0.087799	-0.035173
+5.228238	0.038305	-0.011970	9.846699	0.046098	0.087799	-0.036505
+5.229211	-0.002394	-0.081397	9.846699	0.048629	0.088466	-0.036372
+5.230314	-0.019152	-0.021546	9.858669	0.049828	0.087533	-0.038371
+5.231313	0.052669	-0.033517	9.837123	0.049695	0.088599	-0.039836
+5.232312	0.038305	-0.050275	9.853881	0.048629	0.089265	-0.039570
+5.233313	-0.031123	0.000000	9.870639	0.045698	0.086867	-0.035440
+5.234279	-0.033517	0.011970	9.930490	0.047297	0.086201	-0.033841
+5.235273	0.023940	0.043093	9.827546	0.048363	0.084868	-0.037038
+5.236312	-0.009576	0.002394	9.736573	0.045299	0.086467	-0.040103
+5.237258	-0.004788	0.038305	9.765301	0.045165	0.089132	-0.038237
+5.238309	0.038305	0.083792	9.777271	0.045032	0.090331	-0.036372
+5.239312	0.052669	0.045487	9.827546	0.046764	0.085934	-0.035173
+5.240311	0.052669	0.007182	9.815576	0.045565	0.086067	-0.033441
+5.241313	0.067033	-0.007182	9.861063	0.048096	0.085668	-0.034374
+5.242312	0.098156	0.002394	9.880215	0.046897	0.085002	-0.035173
+5.243254	0.090974	0.023940	9.858669	0.046897	0.086467	-0.036905
+5.244271	0.050275	0.021546	9.808394	0.046764	0.089798	-0.036905
+5.245239	-0.019152	-0.064639	9.789242	0.045832	0.089665	-0.037038
+5.246254	0.002394	0.014364	9.782060	0.044899	0.087799	-0.037971
+5.247274	0.038305	-0.028729	9.801212	0.045965	0.087000	-0.039836
+5.248266	0.033517	-0.009576	9.861063	0.046631	0.086600	-0.036239
+5.249266	0.019152	-0.011970	9.851487	0.048096	0.085934	-0.032642
+5.250264	0.002394	0.035911	9.782060	0.047830	0.088732	-0.035040
+5.251307	-0.064639	0.028729	9.813182	0.046364	0.088332	-0.039170
+5.252310	0.019152	0.050275	9.810788	0.045165	0.089132	-0.040769
+5.253310	0.031123	0.011970	9.758119	0.044766	0.087000	-0.039836
+5.254312	-0.011970	-0.031123	9.794030	0.045832	0.088332	-0.035040
+5.255310	-0.033517	-0.026334	9.815576	0.045432	0.089665	-0.034773
+5.256306	0.040699	-0.004788	9.815576	0.046098	0.087000	-0.036505
+5.257312	0.035911	0.002394	9.885003	0.045565	0.088199	-0.035173
+5.258276	0.009576	-0.016758	9.782060	0.045832	0.088466	-0.036639
+5.259245	0.019152	-0.074215	9.813182	0.046098	0.086334	-0.034240
+5.260230	-0.016758	-0.007182	9.798818	0.046764	0.085668	-0.034107
+5.261311	0.021546	0.035911	9.791636	0.046364	0.088599	-0.039570
+5.262312	0.055063	-0.004788	9.815576	0.046098	0.089931	-0.036106
+5.263311	0.011970	-0.031123	9.782060	0.044499	0.087666	-0.033841
+5.264312	0.031123	-0.014364	9.715026	0.046098	0.086467	-0.033441
+5.265303	0.055063	-0.002394	9.695874	0.047164	0.087000	-0.033441
+5.266312	0.000000	-0.067033	9.772483	0.046764	0.087533	-0.035706
+5.267275	-0.040699	-0.040699	9.779666	0.047164	0.087666	-0.036505
+5.268284	0.023940	-0.014364	9.829940	0.047830	0.085934	-0.037305
+5.269270	0.050275	-0.031123	9.777271	0.047430	0.087266	-0.036505
+5.270312	-0.004788	0.007182	9.729391	0.045565	0.088466	-0.034773
+5.271311	0.002394	0.023940	9.798818	0.045165	0.087000	-0.035706
+5.272311	0.023940	0.002394	9.863457	0.047430	0.087533	-0.036772
+5.273311	0.038305	-0.009576	9.829940	0.048096	0.089665	-0.036639
+5.274290	0.040699	-0.004788	9.796424	0.048629	0.090864	-0.039170
+5.275312	-0.011970	0.016758	9.880215	0.050628	0.088599	-0.035839
+5.276312	0.009576	-0.014364	9.861063	0.049029	0.087133	-0.036239
+5.277246	0.009576	-0.021546	9.817970	0.046764	0.085668	-0.039037
+5.278221	0.040699	0.011970	9.791636	0.047830	0.084469	-0.037571
+5.279220	-0.011970	0.007182	9.808394	0.048496	0.085668	-0.036106
+5.280221	0.028729	-0.038305	9.846699	0.045698	0.089398	-0.034773
+5.281221	0.016758	-0.067033	9.856275	0.045432	0.088599	-0.036639
+5.282215	0.019152	-0.016758	9.829940	0.048096	0.088199	-0.037172
+5.283312	0.014364	-0.026334	9.798818	0.049162	0.087533	-0.032775
+5.284253	0.026334	-0.069427	9.760513	0.048230	0.086867	-0.033841
+5.285211	-0.045487	-0.055063	9.822758	0.047430	0.086067	-0.035440
+5.286206	-0.007182	-0.026334	9.786848	0.048629	0.088066	-0.037038
+5.287205	-0.033517	0.011970	9.837123	0.048230	0.088199	-0.039570
+5.288204	-0.031123	0.002394	9.815576	0.047963	0.085135	-0.037038
+5.289215	0.011970	-0.007182	9.738967	0.045165	0.085002	-0.032508
+5.290206	0.023940	-0.009576	9.712632	0.043833	0.087266	-0.036106
+5.291205	0.038305	-0.023940	9.729391	0.044100	0.089931	-0.037172
+5.292205	-0.007182	-0.019152	9.760513	0.046498	0.090198	-0.038104
+5.293205	0.023940	0.002394	9.707844	0.046098	0.090464	-0.036639
+5.294217	0.050275	0.050275	9.741361	0.047297	0.088199	-0.034907
+5.295218	-0.002394	-0.019152	9.825152	0.049695	0.088332	-0.037172
+5.296215	0.021546	0.014364	9.853881	0.050228	0.090331	-0.033708
+5.297215	0.059851	0.007182	9.837123	0.049828	0.087933	-0.035173
+5.298215	0.059851	-0.069427	9.741361	0.047430	0.088998	-0.036772
+5.299210	0.062245	-0.043093	9.801212	0.045299	0.089398	-0.037971
+5.300288	0.004788	0.059851	9.772483	0.044499	0.088199	-0.037038
+5.301240	0.038305	0.062245	9.736573	0.044499	0.087000	-0.038637
+5.302307	-0.002394	0.019152	9.722208	0.044899	0.087933	-0.038104
+5.303307	0.021546	0.000000	9.758119	0.045432	0.086467	-0.036106
+5.304306	0.047881	-0.028729	9.736573	0.047564	0.087000	-0.034374
+5.305316	0.035911	0.000000	9.731785	0.047031	0.089132	-0.038637
+5.306289	0.055063	-0.007182	9.729391	0.047430	0.090997	-0.041302
+5.307307	0.035911	0.014364	9.736573	0.045698	0.089665	-0.039037
+5.308298	0.050275	0.045487	9.676722	0.045032	0.087266	-0.035306
+5.309305	0.043093	0.050275	9.789242	0.045698	0.086734	-0.035972
+5.310308	0.009576	0.009576	9.815576	0.047297	0.088466	-0.035306
+5.311300	0.002394	-0.021546	9.810788	0.048230	0.089665	-0.037172
+5.312303	0.004788	-0.004788	9.863457	0.046764	0.088599	-0.036505
+5.313307	-0.019152	-0.004788	9.851487	0.046098	0.088466	-0.035440
+5.314304	-0.014364	-0.040699	9.839517	0.048096	0.087400	-0.038371
+5.315288	-0.067033	-0.016758	9.827546	0.048629	0.088466	-0.036372
+5.316267	-0.071821	-0.002394	9.849093	0.048096	0.089265	-0.037704
+5.317293	-0.011970	-0.033517	9.796424	0.048363	0.088199	-0.033841
+5.318250	0.043093	0.019152	9.841911	0.047164	0.086867	-0.032775
+5.319305	0.064639	-0.011970	9.798818	0.047164	0.089132	-0.037305
+5.320305	0.016758	-0.016758	9.741361	0.047031	0.088466	-0.039969
+5.321306	-0.028729	0.009576	9.753331	0.047031	0.087799	-0.038104
+5.322275	0.023940	-0.043093	9.789242	0.048629	0.088066	-0.038770
+5.323248	0.011970	-0.050275	9.837123	0.049162	0.090464	-0.037438
+5.324246	0.002394	-0.033517	9.798818	0.047697	0.089931	-0.038504
+5.325262	0.000000	0.016758	9.789242	0.046364	0.089665	-0.036905
+5.326241	0.043093	0.028729	9.707844	0.045565	0.088865	-0.035706
+5.327251	0.004788	-0.038305	9.777271	0.044233	0.086334	-0.038371
+5.328295	0.019152	-0.031123	9.810788	0.045299	0.086600	-0.037172
+5.329302	-0.014364	-0.016758	9.796424	0.047164	0.087799	-0.035972
+5.330305	0.023940	0.002394	9.767695	0.047697	0.085934	-0.035706
+5.331305	0.023940	0.011970	9.815576	0.046897	0.086867	-0.036106
+5.332307	-0.009576	-0.021546	9.832334	0.048230	0.089265	-0.034640
+5.333300	-0.014364	-0.035911	9.798818	0.048096	0.091130	-0.034773
+5.334302	0.033517	-0.043093	9.829940	0.046631	0.088998	-0.036505
+5.335295	-0.064639	-0.019152	9.865851	0.046764	0.087133	-0.039037
+5.336298	-0.004788	0.043093	9.877821	0.046897	0.086201	-0.038237
+5.337261	0.035911	0.009576	9.832334	0.047963	0.086467	-0.036372
+5.338267	0.026334	0.019152	9.806000	0.048496	0.088998	-0.035306
+5.339277	0.028729	0.007182	9.839517	0.046897	0.089265	-0.034240
+5.340260	-0.007182	0.021546	9.880215	0.047297	0.089132	-0.037038
+5.341307	0.004788	-0.031123	9.760513	0.047697	0.084868	-0.038237
+5.342302	0.033517	-0.047881	9.736573	0.047164	0.085534	-0.036772
+5.343306	0.002394	0.002394	9.777271	0.045299	0.086334	-0.036772
+5.344305	0.007182	0.023940	9.803606	0.042900	0.087400	-0.036372
+5.345244	-0.011970	0.031123	9.839517	0.045165	0.087133	-0.035573
+5.346270	0.014364	0.002394	9.837123	0.047830	0.088332	-0.036239
+5.347294	-0.031123	-0.026334	9.774877	0.047830	0.089265	-0.036639
+5.348238	-0.019152	-0.016758	9.784454	0.047031	0.090064	-0.035706
+5.349303	-0.016758	-0.038305	9.918520	0.046364	0.088199	-0.034374
+5.350307	-0.002394	-0.031123	9.868245	0.044766	0.087799	-0.036772
+5.351235	0.019152	-0.009576	9.875427	0.043167	0.090730	-0.036772
+5.352307	-0.004788	-0.019152	9.794030	0.043300	0.092329	-0.038504
+5.353307	-0.007182	-0.007182	9.820364	0.046631	0.091130	-0.035573
+5.354307	0.000000	0.043093	9.806000	0.047164	0.090597	-0.033308
+5.355305	0.014364	-0.014364	9.779666	0.048629	0.085934	-0.035040
+5.356307	0.033517	0.009576	9.738967	0.046498	0.086734	-0.036905
+5.357277	0.076609	0.052669	9.798818	0.044233	0.089531	-0.039436
+5.358292	-0.004788	-0.002394	9.877821	0.045832	0.090331	-0.039836
+5.359303	0.004788	-0.026334	9.832334	0.046498	0.089398	-0.036106
+5.360252	0.043093	-0.045487	9.801212	0.045299	0.086201	-0.033441
+5.361305	0.074215	-0.028729	9.827546	0.045832	0.087533	-0.036505
+5.362307	-0.023940	-0.014364	9.779666	0.046897	0.091530	-0.037971
+5.363301	0.035911	0.040699	9.777271	0.046631	0.089398	-0.034907
+5.364306	0.004788	0.035911	9.801212	0.047031	0.087666	-0.035306
+5.365306	0.033517	-0.023940	9.779666	0.045432	0.089398	-0.037971
+5.366306	0.019152	-0.033517	9.837123	0.045299	0.088998	-0.037305
+5.367296	0.055063	0.023940	9.786848	0.046631	0.086600	-0.037305
+5.368296	0.026334	0.000000	9.796424	0.048230	0.087266	-0.037571
+5.369309	0.009576	-0.038305	9.784454	0.048230	0.086867	-0.039037
+5.370307	-0.033517	0.000000	9.806000	0.046897	0.086867	-0.036239
+5.371305	-0.021546	-0.031123	9.832334	0.047031	0.090464	-0.031975
+5.372305	-0.011970	-0.004788	9.827546	0.045299	0.086867	-0.034907
+5.373304	-0.028729	-0.016758	9.858669	0.047963	0.087133	-0.038104
+5.374297	0.033517	-0.007182	9.782060	0.047697	0.086067	-0.035306
+5.375312	-0.016758	0.007182	9.844305	0.047830	0.086067	-0.035706
+5.376305	0.033517	0.021546	9.858669	0.046364	0.085668	-0.035040
+5.377249	0.021546	0.004788	9.784454	0.044766	0.086467	-0.034374
+5.378238	-0.007182	0.016758	9.858669	0.045698	0.086734	-0.035440
+5.379290	-0.014364	0.057457	9.849093	0.046631	0.087133	-0.037438
+5.380305	0.023940	0.011970	9.784454	0.045432	0.086201	-0.037305
+5.381306	-0.014364	-0.009576	9.858669	0.045165	0.084735	-0.038237
+5.382246	0.052669	0.014364	9.937672	0.046498	0.086067	-0.036239
+5.383272	0.043093	-0.016758	9.834729	0.046897	0.090064	-0.034240
+5.384249	0.074215	-0.019152	9.832334	0.045965	0.090464	-0.034240
+5.385257	0.026334	-0.028729	9.851487	0.044499	0.089132	-0.036239
+5.386305	0.019152	-0.031123	9.825152	0.045698	0.087133	-0.037571
+5.387249	0.009576	0.016758	9.858669	0.049429	0.085268	-0.037438
+5.388246	0.016758	-0.016758	9.765301	0.049029	0.085534	-0.035839
+5.389235	-0.016758	0.007182	9.865851	0.047564	0.087400	-0.034640
+5.390301	-0.023940	0.028729	9.789242	0.046364	0.086467	-0.036505
+5.391305	-0.026334	0.016758	9.813182	0.047031	0.087133	-0.035706
+5.392262	-0.019152	0.009576	9.815576	0.046897	0.088466	-0.036505
+5.393213	0.004788	0.019152	9.810788	0.044366	0.088332	-0.036505
+5.394247	-0.064639	0.064639	9.806000	0.046897	0.088332	-0.037704
+5.395248	0.021546	0.031123	9.760513	0.049429	0.091263	-0.036106
+5.396305	0.067033	-0.014364	9.726997	0.050095	0.089265	-0.034773
+5.397303	0.076609	0.002394	9.789242	0.047697	0.087133	-0.033175
+5.398306	0.043093	-0.031123	9.846699	0.047031	0.086734	-0.036106
+5.399282	0.007182	-0.031123	9.782060	0.046098	0.089931	-0.037172
+5.400288	0.023940	-0.011970	9.825152	0.047564	0.087266	-0.038637
+5.401248	-0.023940	-0.067033	9.870639	0.048096	0.085268	-0.042368
+5.402290	-0.014364	-0.021546	9.810788	0.048496	0.087533	-0.039037
+5.403304	0.016758	0.000000	9.786848	0.049029	0.090064	-0.036639
+5.404304	0.009576	-0.023940	9.782060	0.048629	0.088865	-0.035440
+5.405290	0.004788	-0.011970	9.772483	0.048496	0.087000	-0.037172
+5.406270	0.047881	-0.031123	9.822758	0.048496	0.086867	-0.038504
+5.407237	0.062245	-0.009576	9.880215	0.045165	0.088998	-0.038504
+5.408219	-0.031123	-0.014364	9.767695	0.045565	0.089132	-0.035972
+5.409261	-0.052669	0.004788	9.858669	0.048363	0.090064	-0.035839
+5.410286	0.033517	0.002394	9.820364	0.049695	0.087400	-0.033574
+5.411318	0.014364	-0.016758	9.798818	0.048230	0.088998	-0.033841
+5.412244	0.043093	0.007182	9.748543	0.045698	0.091263	-0.033974
+5.413262	-0.014364	-0.019152	9.801212	0.044499	0.088466	-0.035040
+5.414308	0.009576	-0.081397	9.827546	0.045965	0.086334	-0.036505
+5.415303	-0.021546	-0.021546	9.762907	0.046231	0.086600	-0.034507
+5.416307	-0.009576	-0.045487	9.695874	0.048363	0.084868	-0.034773
+5.417275	0.040699	-0.033517	9.794030	0.046098	0.087799	-0.036372
+5.418276	0.079003	-0.023940	9.806000	0.046098	0.086867	-0.036372
+5.419306	0.062245	-0.028729	9.762907	0.047697	0.089798	-0.035173
+5.420299	0.004788	-0.038305	9.837123	0.049429	0.089398	-0.036372
+5.421304	0.000000	-0.014364	9.801212	0.048496	0.089265	-0.036372
+5.422251	0.031123	-0.033517	9.772483	0.048896	0.087666	-0.036772
+5.423305	-0.007182	0.000000	9.815576	0.049695	0.088199	-0.035839
+5.424304	-0.021546	0.026334	9.801212	0.048496	0.085135	-0.035839
+5.425286	-0.074215	-0.021546	9.753331	0.046764	0.083936	-0.039170
+5.426252	-0.028729	0.002394	9.777271	0.046764	0.087400	-0.036106
+5.427305	0.009576	0.023940	9.755725	0.047963	0.089665	-0.034907
+5.428237	0.002394	0.055063	9.729391	0.047164	0.089265	-0.033175
+5.429303	0.038305	0.031123	9.746149	0.045032	0.088466	-0.036106
+5.430305	-0.016758	0.002394	9.724603	0.043567	0.087666	-0.035972
+5.431266	-0.038305	0.038305	9.846699	0.046631	0.088332	-0.033041
+5.432282	-0.023940	-0.016758	9.925702	0.047031	0.089531	-0.031975
+5.433315	0.000000	-0.045487	9.923308	0.047297	0.091397	-0.038104
+5.434306	0.055063	0.009576	9.894580	0.046498	0.088466	-0.038770
+5.435277	0.045487	0.011970	9.770089	0.045432	0.087666	-0.037305
+5.436305	-0.007182	-0.019152	9.729391	0.045432	0.087266	-0.034507
+5.437305	-0.040699	0.031123	9.703056	0.049429	0.085668	-0.035706
+5.438307	-0.045487	-0.019152	9.698268	0.048496	0.088998	-0.038504
+5.439304	-0.021546	-0.059851	9.750937	0.047697	0.091796	-0.039170
+5.440305	0.062245	-0.050275	9.892186	0.047031	0.089798	-0.034640
+5.441285	0.038305	-0.002394	9.858669	0.048096	0.089265	-0.033974
+5.442291	0.033517	-0.007182	9.832334	0.048629	0.090464	-0.035573
+5.443307	0.016758	-0.011970	9.784454	0.047697	0.088599	-0.039969
+5.444305	0.026334	0.000000	9.789242	0.045432	0.087799	-0.041168
+5.445306	-0.016758	0.038305	9.882609	0.045832	0.087266	-0.037438
+5.446305	-0.011970	-0.031123	9.822758	0.048629	0.087933	-0.037571
+5.447305	-0.007182	-0.002394	9.882609	0.048896	0.086867	-0.037438
+5.448305	0.021546	0.043093	9.832334	0.046897	0.087400	-0.037438
+5.449290	-0.004788	-0.016758	9.753331	0.045698	0.086067	-0.033441
+5.450256	-0.045487	0.009576	9.810788	0.047031	0.088199	-0.033441
+5.451282	-0.057457	0.064639	9.837123	0.046764	0.089265	-0.034773
+5.452286	0.021546	0.052669	9.820364	0.047697	0.086867	-0.035040
+5.453285	0.033517	-0.009576	9.803606	0.046498	0.087266	-0.037438
+5.454280	0.011970	-0.028729	9.712632	0.045832	0.089531	-0.037438
+5.455305	-0.019152	-0.019152	9.760513	0.046364	0.088599	-0.034240
+5.456304	-0.031123	-0.033517	9.774877	0.047164	0.085801	-0.034907
+5.457306	0.035911	-0.043093	9.726997	0.049029	0.085801	-0.037704
+5.458248	0.052669	-0.016758	9.726997	0.048096	0.087799	-0.035573
+5.459282	0.009576	0.019152	9.784454	0.045565	0.088199	-0.035040
+5.460304	-0.016758	0.000000	9.810788	0.045565	0.087533	-0.033841
+5.461305	-0.014364	-0.007182	9.868245	0.047430	0.087799	-0.035040
+5.462291	-0.002394	-0.007182	9.839517	0.046631	0.089132	-0.036772
+5.463301	0.043093	-0.016758	9.832334	0.046498	0.089265	-0.037438
+5.464305	0.033517	-0.014364	9.806000	0.047164	0.088066	-0.035573
+5.465307	-0.043093	-0.059851	9.794030	0.046631	0.088199	-0.035706
+5.466306	-0.033517	-0.007182	9.798818	0.048230	0.088466	-0.033841
+5.467302	0.000000	0.011970	9.777271	0.047164	0.085401	-0.033041
+5.468229	-0.009576	-0.016758	9.817970	0.046231	0.084202	-0.034240
+5.469306	0.028729	0.062245	9.820364	0.044233	0.085534	-0.037971
+5.470304	0.033517	0.016758	9.762907	0.047164	0.086334	-0.038637
+5.471303	0.000000	-0.009576	9.729391	0.049296	0.087533	-0.037172
+5.472296	-0.057457	0.021546	9.839517	0.048096	0.086734	-0.036905
+5.473302	-0.019152	-0.011970	9.803606	0.045565	0.085401	-0.037838
+5.474306	0.021546	0.028729	9.832334	0.043833	0.086201	-0.037038
+5.475247	-0.007182	-0.033517	9.875427	0.046364	0.087933	-0.034507
+5.476300	0.019152	-0.014364	9.777271	0.047830	0.086867	-0.034374
+5.477305	-0.007182	0.023940	9.813182	0.047963	0.087400	-0.034907
+5.478265	0.023940	-0.028729	9.873033	0.047164	0.088998	-0.038371
+5.479304	0.002394	-0.014364	9.794030	0.048363	0.088599	-0.038637
+5.480247	-0.002394	0.009576	9.851487	0.049162	0.090730	-0.037838
+5.481228	-0.004788	0.033517	9.806000	0.045965	0.092329	-0.040902
+5.482265	0.062245	-0.009576	9.841911	0.046364	0.089265	-0.040236
+5.483270	0.050275	-0.009576	9.935278	0.047430	0.085268	-0.036239
+5.484290	0.000000	0.026334	9.837123	0.043700	0.086734	-0.035040
+5.485254	0.028729	0.038305	9.846699	0.043833	0.087133	-0.035839
+5.486304	0.059851	-0.023940	9.844305	0.048496	0.088466	-0.036372
+5.487262	-0.009576	-0.021546	9.846699	0.048896	0.089398	-0.036505
+5.488262	-0.055063	-0.011970	9.827546	0.049828	0.091397	-0.036505
+5.489306	-0.067033	-0.009576	9.834729	0.048629	0.091130	-0.035440
+5.490305	-0.021546	0.026334	9.801212	0.047430	0.086334	-0.037305
+5.491242	-0.014364	0.045487	9.782060	0.044899	0.084868	-0.037038
+5.492255	0.043093	-0.016758	9.806000	0.045565	0.087133	-0.036372
+5.493297	0.000000	-0.026334	9.887397	0.047297	0.090997	-0.037571
+5.494264	-0.045487	0.045487	9.834729	0.046764	0.089798	-0.038637
+5.495259	0.007182	-0.019152	9.762907	0.047963	0.088066	-0.037438
+5.496283	0.033517	0.002394	9.734179	0.046631	0.087799	-0.032775
+5.497307	0.007182	-0.014364	9.758119	0.047430	0.087000	-0.033308
+5.498305	0.028729	0.023940	9.791636	0.047164	0.086467	-0.038237
+5.499305	-0.011970	0.047881	9.829940	0.045832	0.085668	-0.039703
+5.500305	-0.019152	-0.014364	9.825152	0.046364	0.088998	-0.035573
+5.501305	-0.014364	-0.004788	9.873033	0.046231	0.091130	-0.033708
+5.502306	0.035911	0.021546	9.801212	0.048230	0.089665	-0.033041
+5.503302	0.033517	0.011970	9.772483	0.048629	0.089132	-0.035839
+5.504304	-0.002394	-0.057457	9.808394	0.048363	0.089665	-0.037704
+5.505285	-0.062245	-0.040699	9.839517	0.045565	0.089931	-0.034640
+5.506289	-0.047881	-0.011970	9.829940	0.045299	0.088998	-0.032242
+5.507306	0.002394	-0.004788	9.820364	0.046364	0.088066	-0.035573
+5.508283	0.009576	0.033517	9.868245	0.048496	0.086734	-0.035573
+5.509246	0.028729	0.071821	9.753331	0.048763	0.085135	-0.035040
+5.510305	0.004788	0.081397	9.729391	0.048096	0.087799	-0.036772
+5.511304	0.021546	0.026334	9.794030	0.047963	0.088466	-0.034107
+5.512303	0.040699	-0.038305	9.736573	0.048763	0.087000	-0.034374
+5.513306	0.016758	-0.021546	9.863457	0.048629	0.084735	-0.035839
+5.514304	-0.011970	-0.004788	9.870639	0.046498	0.087000	-0.035706
+5.515269	-0.014364	-0.004788	9.892186	0.045965	0.089265	-0.036772
+5.516287	-0.009576	0.000000	9.786848	0.044899	0.089132	-0.035972
+5.517303	0.019152	-0.011970	9.688692	0.043567	0.088199	-0.035173
+5.518302	0.043093	0.014364	9.734179	0.044632	0.087533	-0.037438
+5.519299	0.033517	0.026334	9.731785	0.047430	0.087533	-0.035972
+5.520303	0.055063	0.021546	9.724603	0.047830	0.089665	-0.032908
+5.521305	0.033517	-0.007182	9.738967	0.046897	0.090464	-0.034640
+5.522305	0.043093	0.038305	9.753331	0.044100	0.090331	-0.040369
+5.523299	0.064639	-0.007182	9.734179	0.043966	0.089665	-0.041701
+5.524306	-0.007182	-0.059851	9.774877	0.048096	0.089132	-0.035573
+5.525245	-0.021546	0.007182	9.844305	0.048629	0.089798	-0.032242
+5.526268	0.000000	-0.007182	9.832334	0.047830	0.088199	-0.033441
+5.527286	0.004788	-0.040699	9.827546	0.046364	0.086334	-0.033041
+5.528292	-0.014364	-0.007182	9.782060	0.046498	0.088599	-0.031975
+5.529302	0.002394	0.038305	9.806000	0.046631	0.086867	-0.035573
+5.530306	-0.031123	0.004788	9.782060	0.044766	0.085801	-0.041168
+5.531303	-0.009576	-0.050275	9.779666	0.045299	0.087000	-0.042501
+5.532243	0.011970	-0.016758	9.832334	0.048496	0.085534	-0.038770
+5.533304	0.002394	0.004788	9.789242	0.050095	0.086734	-0.035440
+5.534308	0.055063	-0.016758	9.861063	0.043567	0.087400	-0.035173
+5.535309	0.019152	0.014364	9.892186	0.043300	0.090864	-0.035040
+5.536301	0.059851	-0.002394	9.911338	0.045698	0.091930	-0.037038
+5.537326	0.019152	0.043093	9.810788	0.047830	0.089398	-0.038237
+5.538248	-0.016758	0.000000	9.798818	0.045965	0.086067	-0.036639
+5.539241	0.014364	0.047881	9.772483	0.044632	0.084469	-0.039969
+5.540306	0.000000	0.033517	9.813182	0.048230	0.088732	-0.036905
+5.541308	-0.014364	-0.002394	9.851487	0.048629	0.088865	-0.035173
+5.542302	-0.028729	-0.023940	9.777271	0.048496	0.088466	-0.037971
+5.543308	0.004788	-0.031123	9.741361	0.049296	0.089531	-0.039570
+5.544308	-0.019152	0.007182	9.767695	0.045965	0.092196	-0.035306
+5.545309	-0.004788	0.040699	9.794030	0.047830	0.091130	-0.033841
+5.546294	-0.052669	0.014364	9.786848	0.048629	0.087133	-0.033308
+5.547281	-0.047881	-0.011970	9.822758	0.047564	0.085801	-0.033708
+5.548241	0.023940	0.055063	9.825152	0.045165	0.086201	-0.034773
+5.549311	0.067033	0.021546	9.712632	0.044899	0.086600	-0.033441
+5.550312	0.033517	-0.033517	9.741361	0.045698	0.088732	-0.034907
+5.551309	-0.021546	-0.004788	9.844305	0.048763	0.089398	-0.036239
+5.552287	0.011970	-0.019152	9.784454	0.047564	0.086467	-0.032642
+5.553310	0.016758	0.026334	9.806000	0.047031	0.085534	-0.034640
+5.554304	0.035911	-0.026334	9.844305	0.047830	0.087000	-0.031842
+5.555308	0.045487	-0.045487	9.827546	0.048896	0.086600	-0.035173
+5.556293	0.076609	-0.059851	9.944854	0.049296	0.085002	-0.037172
+5.557313	0.033517	-0.047881	9.798818	0.049296	0.087000	-0.037172
+5.558311	-0.038305	-0.002394	9.738967	0.049562	0.087533	-0.035706
+5.559268	-0.040699	0.033517	9.810788	0.049828	0.088199	-0.037172
+5.560308	-0.047881	-0.011970	9.810788	0.046364	0.091796	-0.035306
+5.561289	0.014364	0.038305	9.774877	0.045432	0.090198	-0.033708
+5.562313	0.050275	0.009576	9.813182	0.043833	0.088732	-0.035173
+5.563309	0.052669	0.047881	9.806000	0.044632	0.088332	-0.035040
+5.564310	0.031123	0.083792	9.844305	0.050095	0.088732	-0.036772
+5.565306	0.043093	0.019152	9.834729	0.051827	0.085534	-0.040236
+5.566295	0.069427	-0.023940	9.803606	0.048763	0.084335	-0.039703
+5.567320	0.016758	-0.026334	9.844305	0.047297	0.087000	-0.036505
+5.568293	0.011970	-0.043093	9.827546	0.046231	0.086201	-0.034907
+5.569247	0.026334	-0.014364	9.758119	0.047963	0.087666	-0.035706
+5.570310	-0.007182	-0.021546	9.753331	0.047297	0.088199	-0.038237
+5.571308	-0.007182	-0.043093	9.779666	0.047031	0.087266	-0.037038
+5.572309	-0.014364	0.002394	9.777271	0.048896	0.085668	-0.036772
+5.573309	-0.031123	-0.016758	9.825152	0.048896	0.087133	-0.036772
+5.574309	-0.007182	-0.021546	9.849093	0.048363	0.087400	-0.036772
+5.575252	-0.011970	0.033517	9.777271	0.047830	0.088466	-0.036505
+5.576262	0.064639	0.000000	9.729391	0.047297	0.087799	-0.038237
+5.577333	0.033517	-0.021546	9.712632	0.044766	0.087533	-0.036106
+5.578246	0.040699	0.002394	9.784454	0.043700	0.087666	-0.035706
+5.579307	0.045487	0.000000	9.839517	0.045165	0.086734	-0.034773
+5.580307	-0.004788	0.047881	9.901762	0.046631	0.086334	-0.034640
+5.581307	0.016758	-0.007182	9.834729	0.047697	0.086467	-0.037704
+5.582311	-0.038305	-0.040699	9.856275	0.045965	0.087133	-0.041302
+5.583309	0.026334	-0.026334	9.882609	0.048096	0.088332	-0.039303
+5.584250	-0.021546	-0.023940	9.822758	0.049562	0.089531	-0.039436
+5.585242	-0.047881	-0.026334	9.789242	0.045565	0.087799	-0.037838
+5.586272	-0.011970	-0.050275	9.827546	0.043300	0.089132	-0.036639
+5.587332	0.040699	-0.014364	9.829940	0.045032	0.088732	-0.038504
+5.588270	0.019152	-0.016758	9.815576	0.045432	0.088332	-0.036372
+5.589308	0.033517	-0.004788	9.784454	0.049029	0.088332	-0.035040
+5.590310	-0.016758	-0.016758	9.791636	0.047297	0.090464	-0.037172
+5.591309	-0.090974	-0.004788	9.815576	0.045432	0.089132	-0.035440
+5.592307	0.014364	-0.004788	9.770089	0.047564	0.084735	-0.035839
+5.593308	0.033517	0.023940	9.873033	0.047564	0.086201	-0.034374
+5.594308	0.040699	0.023940	9.803606	0.046764	0.089931	-0.036106
+5.595270	-0.019152	0.011970	9.887397	0.044100	0.088466	-0.035173
+5.596295	-0.007182	-0.004788	9.875427	0.045299	0.090730	-0.035306
+5.597309	0.023940	-0.002394	9.794030	0.045299	0.087933	-0.035706
+5.598308	0.023940	-0.011970	9.851487	0.047031	0.085401	-0.037438
+5.599307	-0.014364	-0.023940	9.853881	0.048629	0.086734	-0.039969
+5.600307	0.023940	0.002394	9.877821	0.047830	0.090597	-0.038637
+5.601268	-0.004788	0.040699	9.861063	0.045832	0.090597	-0.037838
+5.602308	0.019152	-0.033517	9.760513	0.046098	0.087000	-0.036505
+5.603303	0.043093	-0.026334	9.758119	0.042767	0.087933	-0.035306
+5.604307	0.067033	-0.016758	9.691086	0.043034	0.089265	-0.034773
+5.605261	0.023940	0.004788	9.815576	0.047164	0.088998	-0.034640
+5.606318	-0.011970	-0.009576	9.868245	0.048096	0.089798	-0.035173
+5.607308	-0.004788	-0.064639	9.846699	0.046231	0.089531	-0.035040
+5.608308	-0.009576	-0.021546	9.786848	0.047430	0.085534	-0.039303
+5.609310	-0.019152	0.007182	9.846699	0.047963	0.085135	-0.037838
+5.610278	-0.023940	-0.047881	9.817970	0.045032	0.087133	-0.036639
+5.611305	0.007182	0.014364	9.743755	0.045032	0.089531	-0.038371
+5.612309	-0.033517	0.016758	9.767695	0.045832	0.088066	-0.038371
+5.613308	-0.033517	-0.033517	9.782060	0.049029	0.084335	-0.040236
+5.614318	-0.023940	0.019152	9.820364	0.046897	0.083136	-0.039703
+5.615289	-0.021546	-0.023940	9.873033	0.043167	0.086734	-0.039037
+5.616310	-0.011970	0.038305	9.896974	0.043567	0.087799	-0.036905
+5.617309	-0.002394	-0.031123	9.846699	0.046764	0.088066	-0.037704
+5.618241	0.033517	-0.019152	9.810788	0.049429	0.087266	-0.036372
+5.619307	0.014364	-0.028729	9.803606	0.047697	0.087799	-0.033974
+5.620307	0.011970	0.011970	9.779666	0.044632	0.087799	-0.037838
+5.621307	0.045487	-0.038305	9.770089	0.045032	0.086734	-0.037305
+5.622311	0.047881	-0.019152	9.767695	0.048230	0.086600	-0.031709
+5.623306	0.059851	0.055063	9.777271	0.049296	0.087666	-0.030776
+5.624273	0.069427	0.045487	9.894580	0.049162	0.086334	-0.033574
+5.625246	0.040699	0.033517	9.827546	0.046364	0.085268	-0.039037
+5.626307	0.014364	-0.011970	9.786848	0.047164	0.088466	-0.037971
+5.627308	0.019152	-0.014364	9.825152	0.046364	0.086201	-0.035706
+5.628302	0.016758	-0.040699	9.858669	0.045965	0.086734	-0.032642
+5.629309	0.021546	0.019152	9.877821	0.047164	0.087266	-0.033441
+5.630309	-0.074215	-0.014364	9.875427	0.045832	0.086600	-0.037038
+5.631308	-0.009576	-0.038305	9.853881	0.045965	0.087933	-0.037704
+5.632308	-0.016758	-0.047881	9.820364	0.047031	0.086201	-0.037571
+5.633302	-0.007182	0.014364	9.791636	0.048629	0.086067	-0.036106
+5.634309	0.016758	0.035911	9.794030	0.047164	0.087533	-0.035573
+5.635262	-0.014364	0.000000	9.806000	0.047430	0.087400	-0.036772
+5.636332	-0.016758	0.014364	9.774877	0.048629	0.087266	-0.036772
+5.637306	-0.079003	0.011970	9.875427	0.047963	0.088066	-0.034640
+5.638309	0.021546	-0.007182	9.832334	0.046498	0.091263	-0.036772
+5.639308	0.014364	0.021546	9.777271	0.047430	0.088066	-0.036772
+5.640309	0.009576	0.040699	9.846699	0.047963	0.087533	-0.032908
+5.641310	-0.023940	0.019152	9.892186	0.047430	0.088332	-0.033841
+5.642310	0.052669	-0.043093	9.777271	0.046498	0.087799	-0.036505
+5.643309	0.057457	-0.021546	9.664751	0.044100	0.086600	-0.038237
+5.644307	0.014364	-0.016758	9.825152	0.046098	0.088332	-0.038770
+5.645268	0.007182	-0.014364	9.829940	0.046231	0.088599	-0.039836
+5.646311	-0.021546	-0.007182	9.827546	0.045832	0.089531	-0.036372
+5.647310	0.045487	-0.031123	9.817970	0.045698	0.088865	-0.035839
+5.648239	0.064639	0.000000	9.827546	0.047297	0.090464	-0.038770
+5.649324	0.035911	-0.069427	9.772483	0.047697	0.088066	-0.039303
+5.650309	0.021546	-0.033517	9.774877	0.045832	0.087000	-0.036905
+5.651305	0.014364	0.007182	9.875427	0.045299	0.086201	-0.033574
+5.652306	-0.031123	0.009576	9.815576	0.048096	0.086467	-0.033574
+5.653308	-0.004788	0.071821	9.779666	0.047430	0.087666	-0.036505
+5.654286	0.033517	0.028729	9.827546	0.047297	0.087799	-0.036372
+5.655279	0.081397	-0.004788	9.803606	0.046498	0.089665	-0.033041
+5.656313	0.088580	0.026334	9.724603	0.042900	0.089265	-0.034107
+5.657307	0.045487	0.007182	9.741361	0.045032	0.087666	-0.036239
+5.658294	-0.035911	-0.014364	9.724603	0.046631	0.088732	-0.039037
+5.659302	0.000000	-0.016758	9.712632	0.046897	0.087933	-0.037038
+5.660307	0.026334	-0.038305	9.767695	0.046764	0.086467	-0.036772
+5.661306	-0.021546	-0.009576	9.743755	0.046364	0.084868	-0.037571
+5.662310	-0.019152	0.004788	9.825152	0.047031	0.086201	-0.038504
+5.663306	-0.023940	-0.026334	9.839517	0.047297	0.085934	-0.035972
+5.664307	-0.035911	0.002394	9.784454	0.045165	0.085801	-0.034374
+5.665280	-0.011970	-0.059851	9.791636	0.045432	0.087266	-0.033841
+5.666273	-0.031123	-0.055063	9.820364	0.047830	0.085668	-0.035173
+5.667308	0.009576	0.021546	9.806000	0.047963	0.086467	-0.033041
+5.668307	-0.007182	-0.026334	9.712632	0.048363	0.087266	-0.032109
+5.669307	0.031123	-0.045487	9.686298	0.049562	0.088332	-0.029577
+5.670310	-0.023940	-0.016758	9.681510	0.048629	0.087133	-0.037704
+5.671307	0.009576	-0.007182	9.755725	0.047963	0.085268	-0.039570
+5.672277	0.064639	0.000000	9.875427	0.048096	0.086600	-0.037571
+5.673307	0.050275	0.009576	9.829940	0.048363	0.088066	-0.037704
+5.674308	-0.019152	-0.026334	9.803606	0.047297	0.088732	-0.035440
+5.675280	0.002394	0.000000	9.817970	0.046231	0.088865	-0.036772
+5.676305	-0.014364	0.031123	9.815576	0.045832	0.086867	-0.036639
+5.677306	-0.019152	0.033517	9.784454	0.046498	0.087000	-0.035440
+5.678239	0.069427	-0.035911	9.746149	0.047031	0.088865	-0.035040
+5.679303	0.000000	-0.062245	9.760513	0.047164	0.090198	-0.038371
+5.680301	-0.047881	-0.026334	9.837123	0.048763	0.091530	-0.039170
+5.681307	0.014364	0.014364	9.822758	0.047031	0.091130	-0.034640
+5.682306	0.031123	0.000000	9.822758	0.045832	0.090064	-0.033175
+5.683308	0.000000	-0.004788	9.794030	0.045432	0.086201	-0.038237
+5.684294	-0.031123	-0.004788	9.760513	0.047297	0.086201	-0.037038
+5.685253	0.028729	0.011970	9.782060	0.047697	0.088732	-0.036772
+5.686274	0.038305	0.014364	9.770089	0.048096	0.089798	-0.033974
+5.687307	0.019152	-0.011970	9.734179	0.047164	0.088865	-0.036905
+5.688309	0.064639	-0.009576	9.810788	0.045165	0.088732	-0.040902
+5.689251	-0.019152	0.031123	9.839517	0.046498	0.086600	-0.039170
+5.690311	-0.055063	0.057457	9.803606	0.047297	0.085668	-0.037038
+5.691307	0.000000	0.007182	9.786848	0.048096	0.085934	-0.035173
+5.692306	0.014364	0.019152	9.798818	0.047697	0.088466	-0.037038
+5.693307	0.007182	0.016758	9.791636	0.046364	0.089531	-0.036639
+5.694265	-0.026334	-0.019152	9.767695	0.046098	0.089132	-0.036905
+5.695289	0.019152	0.007182	9.750937	0.048896	0.091530	-0.037438
+5.696307	-0.014364	-0.009576	9.798818	0.048363	0.087533	-0.035040
+5.697306	0.009576	-0.043093	9.827546	0.046498	0.085534	-0.035573
+5.698259	0.004788	-0.026334	9.865851	0.044632	0.086867	-0.037172
+5.699307	-0.009576	0.000000	9.841911	0.047297	0.089798	-0.036639
+5.700306	-0.011970	0.031123	9.813182	0.047697	0.090730	-0.039037
+5.701238	-0.007182	0.009576	9.839517	0.047564	0.092063	-0.037571
+5.702308	0.011970	-0.009576	9.786848	0.046364	0.091130	-0.034107
+5.703315	0.019152	0.002394	9.705450	0.046098	0.091130	-0.036639
+5.704292	0.047881	0.009576	9.767695	0.047430	0.088466	-0.034773
+5.705306	0.062245	0.011970	9.767695	0.045299	0.086600	-0.034374
+5.706309	0.040699	-0.052669	9.806000	0.043700	0.084602	-0.035839
+5.707303	0.009576	-0.002394	9.719814	0.045565	0.085135	-0.038637
+5.708264	0.009576	-0.040699	9.829940	0.047697	0.085135	-0.038371
+5.709307	0.057457	0.002394	9.868245	0.049695	0.085934	-0.035972
+5.710241	0.000000	-0.014364	9.758119	0.046498	0.088466	-0.033841
+5.711300	0.014364	-0.062245	9.837123	0.046631	0.090997	-0.036372
+5.712304	-0.031123	-0.043093	9.765301	0.046897	0.090730	-0.035972
+5.713276	0.004788	-0.083792	9.803606	0.048363	0.089798	-0.035573
+5.714271	0.031123	-0.016758	9.801212	0.048763	0.087799	-0.035040
+5.715309	0.002394	0.004788	9.851487	0.048763	0.086067	-0.039570
+5.716307	0.004788	-0.028729	9.889792	0.049429	0.086334	-0.039969
+5.717304	-0.011970	-0.004788	9.772483	0.047164	0.087799	-0.034907
+5.718264	-0.021546	0.009576	9.796424	0.045698	0.089531	-0.033574
+5.719305	-0.074215	-0.014364	9.791636	0.045965	0.089132	-0.039570
+5.720306	-0.031123	0.035911	9.738967	0.045432	0.089132	-0.038504
+5.721306	0.045487	0.023940	9.892186	0.044233	0.088066	-0.036106
+5.722307	0.059851	0.052669	9.882609	0.045965	0.090997	-0.035573
+5.723275	-0.050275	0.067033	9.794030	0.047963	0.088066	-0.037305
+5.724268	-0.050275	0.004788	9.762907	0.049962	0.086334	-0.037038
+5.725307	-0.021546	0.043093	9.803606	0.048096	0.086467	-0.036505
+5.726277	-0.031123	-0.014364	9.772483	0.048096	0.087533	-0.037038
+5.727304	-0.055063	-0.031123	9.856275	0.049162	0.087133	-0.034507
+5.728303	-0.055063	-0.023940	9.846699	0.048629	0.088199	-0.034907
+5.729272	-0.023940	0.019152	9.873033	0.047164	0.087266	-0.037038
+5.730307	0.011970	-0.038305	9.806000	0.047830	0.088865	-0.037172
+5.731306	0.031123	0.011970	9.798818	0.048496	0.088998	-0.035706
+5.732304	-0.011970	-0.004788	9.753331	0.046498	0.089798	-0.036772
+5.733268	-0.021546	-0.004788	9.822758	0.047297	0.088732	-0.038904
+5.734291	0.023940	0.026334	9.808394	0.045165	0.083270	-0.035839
+5.735304	0.043093	-0.002394	9.779666	0.046498	0.084069	-0.036772
+5.736265	0.026334	0.038305	9.829940	0.046498	0.089265	-0.031443
+5.737230	-0.023940	0.011970	9.858669	0.044899	0.089531	-0.033708
+5.738233	-0.052669	-0.016758	9.767695	0.046631	0.089265	-0.036239
+5.739235	-0.011970	-0.007182	9.734179	0.047564	0.090198	-0.038104
+5.740306	0.026334	-0.047881	9.770089	0.047830	0.088732	-0.035706
+5.741299	0.014364	-0.052669	9.738967	0.047564	0.086467	-0.033308
+5.742306	0.009576	-0.045487	9.877821	0.047697	0.084868	-0.032508
+5.743277	-0.007182	-0.011970	9.748543	0.048230	0.086600	-0.037038
+5.744275	-0.026334	0.016758	9.820364	0.047164	0.088199	-0.037704
+5.745301	-0.019152	-0.026334	9.868245	0.047697	0.087666	-0.038504
+5.746308	-0.019152	0.026334	9.841911	0.048496	0.085801	-0.036505
+5.747304	-0.031123	0.050275	9.880215	0.047830	0.087000	-0.031709
+5.748305	-0.035911	-0.002394	9.837123	0.048763	0.087799	-0.035573
+5.749300	0.016758	-0.014364	9.779666	0.049695	0.087933	-0.039170
+5.750291	0.045487	-0.014364	9.774877	0.047297	0.088998	-0.039037
+5.751269	0.009576	-0.052669	9.817970	0.044632	0.086201	-0.037571
+5.752304	0.021546	-0.028729	9.832334	0.044899	0.087666	-0.035839
+5.753312	0.016758	-0.057457	9.863457	0.046498	0.090864	-0.034640
+5.754295	0.014364	0.023940	9.846699	0.048096	0.091530	-0.030510
+5.755307	0.021546	-0.004788	9.817970	0.049695	0.089398	-0.033041
+5.756304	0.026334	0.004788	9.772483	0.047297	0.088865	-0.036772
+5.757306	-0.014364	0.038305	9.853881	0.048230	0.085268	-0.035040
+5.758299	-0.002394	0.016758	9.853881	0.047697	0.085934	-0.035173
+5.759306	0.026334	0.050275	9.834729	0.047430	0.089398	-0.032908
+5.760292	0.076609	-0.011970	9.748543	0.048096	0.090997	-0.033308
+5.761307	0.035911	-0.004788	9.803606	0.048629	0.088599	-0.035306
+5.762306	0.011970	-0.002394	9.789242	0.047564	0.087266	-0.037571
+5.763306	-0.040699	0.004788	9.791636	0.045832	0.086734	-0.036639
+5.764284	-0.028729	0.007182	9.825152	0.045698	0.085135	-0.035706
+5.765303	0.014364	0.000000	9.865851	0.048363	0.085934	-0.037971
+5.766306	0.011970	-0.004788	9.774877	0.049828	0.086067	-0.035173
+5.767305	0.028729	-0.023940	9.698268	0.050228	0.085401	-0.032642
+5.768264	0.059851	-0.052669	9.841911	0.050361	0.087799	-0.037038
+5.769256	0.019152	-0.021546	9.815576	0.048763	0.087533	-0.038904
+5.770306	0.009576	-0.011970	9.825152	0.045698	0.086334	-0.035040
+5.771300	-0.021546	0.009576	9.822758	0.044899	0.085401	-0.034374
+5.772304	0.059851	0.028729	9.853881	0.046364	0.088332	-0.035440
+5.773274	0.059851	0.038305	9.827546	0.049695	0.088998	-0.035040
+5.774263	-0.009576	0.023940	9.801212	0.048763	0.088998	-0.032908
+5.775306	-0.007182	0.016758	9.784454	0.045832	0.087799	-0.035040
+5.776293	0.021546	-0.002394	9.810788	0.045965	0.087000	-0.036772
+5.777306	0.086186	0.007182	9.834729	0.047164	0.086600	-0.037571
+5.778303	0.047881	-0.028729	9.808394	0.046764	0.084335	-0.036772
+5.779281	-0.009576	-0.011970	9.791636	0.045299	0.083936	-0.038504
+5.780304	0.002394	0.009576	9.849093	0.046364	0.084868	-0.035706
+5.781307	-0.002394	-0.028729	9.750937	0.047430	0.088732	-0.034374
+5.782307	-0.052669	0.000000	9.803606	0.046897	0.088199	-0.034773
+5.783275	-0.023940	0.004788	9.810788	0.047963	0.085002	-0.038237
+5.784267	0.011970	0.031123	9.803606	0.046764	0.085668	-0.042101
+5.785257	0.043093	0.014364	9.789242	0.048096	0.086334	-0.037438
+5.786258	0.002394	0.050275	9.870639	0.049162	0.087266	-0.034907
+5.787306	0.014364	0.019152	9.837123	0.048763	0.087799	-0.033841
+5.788283	0.002394	0.026334	9.837123	0.047564	0.088199	-0.036772
+5.789303	0.028729	0.040699	9.853881	0.046498	0.090730	-0.035839
+5.790296	0.040699	-0.019152	9.803606	0.048096	0.089665	-0.035972
+5.791303	0.038305	-0.026334	9.765301	0.049429	0.087000	-0.038904
+5.792299	0.050275	0.035911	9.786848	0.050095	0.087666	-0.035972
+5.793279	0.016758	0.000000	9.817970	0.048629	0.088066	-0.036239
+5.794317	0.047881	-0.045487	9.777271	0.046231	0.086467	-0.038904
+5.795305	0.011970	-0.033517	9.765301	0.046098	0.087799	-0.035972
+5.796305	0.028729	-0.023940	9.803606	0.047297	0.086334	-0.036772
+5.797304	0.043093	0.004788	9.770089	0.049162	0.085801	-0.036772
+5.798290	0.038305	0.014364	9.712632	0.047830	0.086734	-0.036905
+5.799305	0.004788	0.007182	9.834729	0.047963	0.087933	-0.035306
+5.800308	0.040699	0.033517	9.851487	0.045698	0.088066	-0.033441
+5.801250	-0.038305	0.019152	9.815576	0.044233	0.090064	-0.036505
+5.802307	0.021546	0.040699	9.789242	0.045432	0.090464	-0.035839
+5.803277	0.050275	0.038305	9.815576	0.046764	0.089931	-0.034773
+5.804287	0.000000	0.035911	9.820364	0.048363	0.088466	-0.034773
+5.805304	0.000000	-0.055063	9.755725	0.047164	0.089531	-0.039170
+5.806301	-0.023940	-0.014364	9.820364	0.047564	0.087666	-0.036372
+5.807306	0.014364	-0.009576	9.908944	0.048496	0.087400	-0.036505
+5.808254	-0.011970	-0.011970	9.861063	0.049162	0.088732	-0.036772
+5.809279	0.007182	0.009576	9.794030	0.046764	0.088199	-0.034640
+5.810307	0.004788	0.031123	9.839517	0.046231	0.086067	-0.037038
+5.811305	-0.014364	-0.035911	9.803606	0.046764	0.085268	-0.036372
+5.812303	-0.028729	-0.011970	9.825152	0.047697	0.085268	-0.038371
+5.813276	-0.026334	0.000000	9.901762	0.048230	0.087133	-0.038504
+5.814290	0.045487	-0.023940	9.782060	0.047297	0.089132	-0.035706
+5.815304	0.035911	0.002394	9.724603	0.045965	0.089132	-0.034773
+5.816305	-0.007182	0.009576	9.794030	0.047697	0.087400	-0.036239
+5.817283	-0.023940	-0.043093	9.825152	0.048096	0.086600	-0.039170
+5.818245	-0.045487	-0.023940	9.762907	0.048096	0.087799	-0.038237
+5.819299	0.000000	0.040699	9.796424	0.045965	0.088998	-0.037838
+5.820303	0.009576	0.035911	9.774877	0.045165	0.089398	-0.037305
+5.821304	-0.014364	0.009576	9.760513	0.047830	0.086734	-0.039170
+5.822306	0.019152	-0.043093	9.784454	0.047297	0.087400	-0.038104
+5.823276	0.023940	-0.021546	9.784454	0.047164	0.088865	-0.036239
+5.824238	-0.002394	0.007182	9.873033	0.045965	0.087666	-0.039170
+5.825275	0.021546	0.009576	9.820364	0.043167	0.085002	-0.038770
+5.826257	0.040699	0.004788	9.755725	0.042101	0.086467	-0.035839
+5.827303	0.059851	-0.031123	9.820364	0.045032	0.089398	-0.035173
+5.828305	0.038305	-0.014364	9.875427	0.046098	0.088599	-0.036106
+5.829304	-0.011970	0.011970	9.789242	0.047031	0.086734	-0.035440
+5.830305	0.009576	-0.009576	9.817970	0.047830	0.086600	-0.035440
+5.831304	0.014364	-0.023940	9.865851	0.049029	0.087266	-0.032642
+5.832299	0.004788	0.031123	9.794030	0.049562	0.089665	-0.034107
+5.833253	-0.038305	0.074215	9.767695	0.049029	0.089398	-0.037172
+5.834307	0.000000	0.021546	9.803606	0.047564	0.087000	-0.038371
+5.835242	-0.004788	0.009576	9.789242	0.047031	0.086201	-0.040369
+5.836303	-0.014364	-0.038305	9.839517	0.048096	0.087000	-0.038504
+5.837244	0.033517	-0.026334	9.798818	0.047697	0.088732	-0.034773
+5.838235	0.019152	-0.016758	9.806000	0.045832	0.089398	-0.033841
+5.839306	-0.019152	0.016758	9.779666	0.045299	0.087933	-0.036372
+5.840278	0.031123	-0.009576	9.803606	0.046364	0.086600	-0.038237
+5.841282	0.050275	-0.055063	9.846699	0.046897	0.085002	-0.037838
+5.842304	0.026334	-0.040699	9.810788	0.046897	0.089398	-0.035040
+5.843276	0.002394	0.019152	9.748543	0.047297	0.090198	-0.037571
+5.844242	-0.014364	0.004788	9.693480	0.042101	0.090464	-0.036372
+5.845304	0.011970	-0.059851	9.698268	0.042501	0.089798	-0.034907
+5.846302	-0.028729	-0.021546	9.825152	0.046631	0.087266	-0.033708
+5.847303	0.014364	-0.007182	9.875427	0.046631	0.085668	-0.036106
+5.848279	0.035911	0.009576	9.810788	0.046631	0.086201	-0.039436
+5.849280	-0.007182	-0.023940	9.703056	0.046631	0.087533	-0.039303
+5.850266	-0.052669	-0.021546	9.712632	0.043833	0.086734	-0.035839
+5.851258	0.009576	-0.033517	9.755725	0.044632	0.089398	-0.034640
+5.852279	0.047881	-0.026334	9.741361	0.046364	0.088199	-0.035839
+5.853279	0.011970	-0.026334	9.837123	0.047297	0.087666	-0.037704
+5.854286	-0.021546	-0.014364	9.856275	0.047164	0.087400	-0.037038
+5.855261	-0.014364	0.000000	9.815576	0.045698	0.086201	-0.035040
+5.856280	0.009576	-0.055063	9.798818	0.046764	0.085668	-0.033974
+5.857244	-0.009576	-0.076609	9.815576	0.046631	0.087799	-0.033308
+5.858281	0.016758	-0.033517	9.794030	0.048496	0.087133	-0.037704
+5.859221	0.033517	0.004788	9.822758	0.048230	0.087666	-0.036905
+5.860203	0.038305	-0.004788	9.798818	0.048230	0.086600	-0.036505
+5.861202	0.019152	-0.004788	9.861063	0.046764	0.085934	-0.036772
+5.862204	0.002394	-0.016758	9.755725	0.046364	0.086734	-0.034507
+5.863183	-0.009576	0.004788	9.777271	0.047564	0.086867	-0.034240
+5.864802	0.028729	0.009576	9.798818	0.047830	0.085268	-0.034107
+5.865204	0.019152	0.004788	9.849093	0.046764	0.083802	-0.033574
+5.866202	0.028729	0.021546	9.880215	0.047564	0.086067	-0.036239
+5.867226	0.007182	-0.023940	9.743755	0.049029	0.087266	-0.037838
+5.868205	0.040699	-0.047881	9.810788	0.047564	0.088732	-0.036106
+5.869243	0.057457	-0.038305	9.820364	0.045165	0.089398	-0.034773
+5.870268	-0.014364	0.016758	9.789242	0.045165	0.088066	-0.035706
+5.871279	-0.038305	-0.026334	9.839517	0.045165	0.086867	-0.035972
+5.872277	-0.014364	0.004788	9.758119	0.044899	0.087666	-0.035306
+5.873242	0.004788	-0.009576	9.753331	0.046631	0.090997	-0.035440
+5.874221	0.031123	-0.031123	9.762907	0.047430	0.090864	-0.036772
+5.875248	0.033517	0.047881	9.810788	0.046764	0.087400	-0.039703
+5.876204	0.021546	0.031123	9.841911	0.046098	0.084335	-0.037438
+5.877271	0.033517	0.014364	9.794030	0.047564	0.087133	-0.036106
+5.878216	0.052669	-0.023940	9.765301	0.048230	0.089132	-0.037172
+5.879236	0.011970	-0.004788	9.810788	0.045698	0.086867	-0.034907
+5.880229	0.019152	0.040699	9.750937	0.044766	0.086600	-0.033708
+5.881304	-0.014364	0.076609	9.825152	0.045965	0.089531	-0.036372
+5.882281	-0.071821	0.007182	9.841911	0.047697	0.090064	-0.036372
+5.883207	-0.028729	-0.031123	9.834729	0.049029	0.087533	-0.034773
+5.884186	-0.021546	-0.031123	9.813182	0.044632	0.085401	-0.033441
+5.885189	-0.004788	-0.019152	9.813182	0.044233	0.084868	-0.034107
+5.886195	-0.031123	0.038305	9.827546	0.045032	0.087133	-0.036772
+5.887202	0.043093	0.016758	9.770089	0.046897	0.086600	-0.035839
+5.888202	0.028729	-0.057457	9.758119	0.048629	0.087000	-0.035972
+5.889204	-0.002394	0.000000	9.844305	0.049562	0.086067	-0.036505
+5.890203	0.014364	-0.004788	9.870639	0.046631	0.086467	-0.036772
+5.891202	0.011970	0.028729	9.861063	0.044766	0.087533	-0.038637
+5.892201	0.026334	0.074215	9.813182	0.045832	0.088332	-0.037038
+5.893203	-0.002394	0.023940	9.789242	0.046764	0.088732	-0.033175
+5.894204	0.035911	-0.026334	9.829940	0.047830	0.089931	-0.032242
+5.895185	0.043093	-0.023940	9.729391	0.049296	0.090464	-0.035839
+5.896179	-0.002394	0.033517	9.729391	0.048496	0.091530	-0.037038
+5.897187	0.055063	0.002394	9.794030	0.048230	0.087400	-0.037305
+5.898204	0.021546	-0.062245	9.760513	0.045565	0.086867	-0.037438
+5.899273	-0.004788	-0.043093	9.810788	0.045165	0.088332	-0.039570
+5.900278	-0.028729	0.081397	9.858669	0.045698	0.088998	-0.038504
+5.901279	-0.023940	0.038305	9.856275	0.046897	0.086334	-0.038104
+5.902269	0.021546	-0.059851	9.863457	0.048763	0.088199	-0.038504
+5.903273	0.040699	-0.043093	9.777271	0.049296	0.087666	-0.039436
+5.904277	0.011970	-0.009576	9.736573	0.046631	0.085801	-0.036106
+5.905278	0.047881	0.004788	9.810788	0.045165	0.086734	-0.036505
+5.906231	0.052669	-0.014364	9.841911	0.047430	0.087799	-0.034240
+5.907304	0.045487	-0.040699	9.774877	0.049029	0.087266	-0.034107
+5.908278	0.023940	-0.033517	9.741361	0.047830	0.089132	-0.036505
+5.909279	-0.033517	-0.043093	9.834729	0.046631	0.090864	-0.038237
+5.910283	-0.031123	-0.004788	9.858669	0.047297	0.089665	-0.039436
+5.911278	-0.007182	0.031123	9.746149	0.046498	0.086467	-0.037438
+5.912279	0.026334	0.002394	9.746149	0.045165	0.087000	-0.036505
+5.913281	0.011970	0.057457	9.803606	0.046364	0.086334	-0.039836
+5.914279	0.047881	0.035911	9.822758	0.049296	0.085534	-0.037704
+5.915280	0.011970	0.002394	9.863457	0.049296	0.087400	-0.035706
+5.916246	-0.004788	-0.009576	9.791636	0.047297	0.088732	-0.033308
+5.917219	0.021546	-0.009576	9.829940	0.046498	0.088199	-0.036239
+5.918197	-0.004788	0.002394	9.798818	0.049296	0.088732	-0.038637
+5.919199	-0.007182	-0.038305	9.758119	0.047430	0.088199	-0.035573
+5.920202	-0.007182	-0.038305	9.734179	0.046631	0.089798	-0.032642
+5.921274	-0.016758	-0.057457	9.810788	0.046498	0.087799	-0.033441
+5.922280	-0.021546	-0.059851	9.810788	0.046897	0.084469	-0.035972
+5.923279	-0.011970	0.074215	9.772483	0.047031	0.087000	-0.035040
+5.924279	-0.040699	-0.019152	9.801212	0.046897	0.090198	-0.033441
+5.925278	-0.007182	-0.023940	9.806000	0.044766	0.088599	-0.034107
+5.926212	0.021546	-0.055063	9.798818	0.043567	0.087799	-0.033574
+5.927248	0.062245	-0.007182	9.741361	0.045832	0.087533	-0.031176
+5.928212	0.031123	0.009576	9.715026	0.045832	0.088599	-0.035706
+5.929282	-0.002394	0.023940	9.839517	0.045565	0.089931	-0.039170
+5.930279	0.059851	0.043093	9.796424	0.045299	0.089798	-0.038371
+5.931278	0.064639	0.057457	9.820364	0.046498	0.091663	-0.037438
+5.932278	0.014364	0.062245	9.806000	0.046231	0.090464	-0.036505
+5.933273	-0.014364	0.009576	9.803606	0.047430	0.088332	-0.035706
+5.934279	0.019152	0.035911	9.858669	0.046498	0.088599	-0.038504
+5.935217	0.026334	0.014364	9.784454	0.045832	0.092063	-0.037571
+5.936279	0.047881	-0.002394	9.731785	0.045832	0.092995	-0.034773
+5.937267	0.038305	0.016758	9.803606	0.045432	0.090864	-0.034240
+5.938253	0.033517	-0.021546	9.815576	0.046498	0.086867	-0.033708
+5.939279	0.009576	-0.011970	9.777271	0.046631	0.084469	-0.034507
+5.940277	0.023940	-0.014364	9.762907	0.046231	0.086734	-0.034507
+5.941278	0.028729	0.038305	9.827546	0.046364	0.086734	-0.037305
+5.942282	-0.023940	-0.023940	9.798818	0.047430	0.087266	-0.040902
+5.943278	0.067033	-0.007182	9.748543	0.046098	0.089665	-0.038637
+5.944277	0.007182	-0.016758	9.796424	0.045032	0.090064	-0.037704
+5.945264	0.059851	-0.014364	9.743755	0.047164	0.088732	-0.038770
+5.946280	-0.011970	-0.055063	9.734179	0.047564	0.085534	-0.036239
+5.947279	-0.031123	0.011970	9.770089	0.047963	0.087666	-0.036905
+5.948261	-0.007182	0.038305	9.820364	0.047963	0.090730	-0.038104
+5.949248	0.011970	0.028729	9.827546	0.046364	0.088599	-0.039303
+5.950223	0.043093	-0.045487	9.858669	0.045698	0.085268	-0.039037
+5.951197	0.016758	-0.055063	9.870639	0.046231	0.083136	-0.035706
+5.952266	0.028729	0.047881	9.794030	0.048763	0.085268	-0.035040
+5.953279	0.009576	-0.011970	9.810788	0.047297	0.088466	-0.034773
+5.954280	0.040699	-0.050275	9.789242	0.044499	0.087400	-0.036372
+5.955274	0.023940	0.031123	9.729391	0.044366	0.086600	-0.037838
+5.956270	0.088580	0.007182	9.806000	0.047164	0.086867	-0.037971
+5.957250	0.052669	-0.038305	9.841911	0.047697	0.087933	-0.037172
+5.958208	0.040699	-0.007182	9.813182	0.046631	0.087266	-0.035040
+5.959265	-0.011970	-0.002394	9.767695	0.045698	0.087000	-0.034240
+5.960273	-0.014364	-0.002394	9.868245	0.046631	0.086867	-0.035040
+5.961279	0.007182	0.000000	9.786848	0.047697	0.085668	-0.034374
+5.962280	0.067033	0.023940	9.686298	0.048230	0.087133	-0.034107
+5.963278	-0.007182	0.016758	9.803606	0.047830	0.090198	-0.035706
+5.964279	0.002394	0.035911	9.851487	0.048230	0.091530	-0.037571
+5.965278	0.038305	-0.011970	9.906550	0.046364	0.089398	-0.035972
+5.966278	0.059851	-0.023940	9.846699	0.048763	0.085534	-0.032242
+5.967272	0.069427	-0.028729	9.774877	0.050894	0.085668	-0.034240
+5.968265	0.079003	-0.055063	9.791636	0.048896	0.087400	-0.036505
+5.969278	0.059851	-0.064639	9.784454	0.047164	0.087933	-0.034640
+5.970280	0.038305	-0.023940	9.808394	0.043966	0.087666	-0.036106
+5.971278	0.021546	-0.019152	9.796424	0.045165	0.087799	-0.036505
+5.972278	0.043093	-0.019152	9.808394	0.048363	0.088865	-0.038770
+5.973279	-0.011970	-0.067033	9.877821	0.048363	0.087133	-0.039969
+5.974279	0.043093	-0.026334	9.808394	0.047297	0.085801	-0.034907
+5.975279	0.038305	-0.023940	9.794030	0.045832	0.087133	-0.033708
+5.976207	0.047881	-0.031123	9.885003	0.047031	0.090464	-0.034107
+5.977250	0.071821	0.002394	9.832334	0.045832	0.089531	-0.036772
+5.978281	0.069427	0.059851	9.882609	0.045698	0.086600	-0.038104
+5.979265	0.004788	0.050275	9.777271	0.047164	0.085268	-0.037838
+5.980278	-0.007182	0.019152	9.777271	0.048363	0.084735	-0.036372
+5.981280	0.019152	0.050275	9.837123	0.048363	0.088066	-0.037172
+5.982261	-0.011970	0.040699	9.810788	0.049029	0.088332	-0.039570
+5.983277	0.011970	-0.038305	9.834729	0.049562	0.088998	-0.037305
+5.984250	-0.007182	-0.035911	9.810788	0.049962	0.087400	-0.037571
+5.985279	0.033517	0.031123	9.796424	0.047564	0.086467	-0.036106
+5.986235	0.002394	0.031123	9.803606	0.045299	0.086467	-0.032375
+5.987237	0.007182	0.000000	9.875427	0.045565	0.088865	-0.035573
+5.988276	0.002394	0.014364	9.794030	0.044766	0.090064	-0.038237
+5.989279	-0.031123	0.019152	9.777271	0.044766	0.088865	-0.035440
+5.990237	-0.011970	-0.016758	9.796424	0.044766	0.088732	-0.036106
+5.991276	0.004788	-0.004788	9.707844	0.045432	0.087799	-0.034374
+5.992276	-0.009576	0.035911	9.748543	0.048496	0.085534	-0.036372
+5.993278	-0.016758	0.033517	9.779666	0.049828	0.084868	-0.036505
+5.994271	0.002394	0.019152	9.801212	0.049429	0.087266	-0.033974
+5.995247	0.000000	-0.014364	9.829940	0.047430	0.087666	-0.033441
+5.996239	-0.021546	0.016758	9.844305	0.047031	0.086067	-0.034374
+5.997278	-0.023940	0.000000	9.834729	0.047830	0.087666	-0.038504
+5.998279	-0.088580	0.002394	9.772483	0.048629	0.088599	-0.039836
+5.999266	-0.055063	0.067033	9.796424	0.049296	0.087266	-0.036505
+6.000277	-0.004788	0.009576	9.782060	0.045698	0.088732	-0.035573
+6.001270	0.033517	0.028729	9.679116	0.044233	0.089132	-0.035972
+6.002279	0.011970	0.014364	9.707844	0.046098	0.089265	-0.037038
+6.003276	0.043093	-0.014364	9.765301	0.048230	0.087000	-0.035573
+6.004279	0.038305	0.026334	9.782060	0.047564	0.087133	-0.033574
+6.005247	-0.009576	0.016758	9.762907	0.044899	0.089132	-0.038104
+6.006274	-0.031123	-0.019152	9.829940	0.045032	0.089931	-0.037838
+6.007252	-0.033517	-0.052669	9.808394	0.047164	0.086467	-0.037571
+6.008203	0.014364	-0.026334	9.858669	0.049962	0.085268	-0.035306
+6.009193	0.009576	-0.043093	9.803606	0.048629	0.086734	-0.031975
+6.010201	0.019152	-0.062245	9.726997	0.046897	0.086334	-0.034374
+6.011277	0.045487	-0.043093	9.748543	0.045299	0.086867	-0.034507
+6.012277	0.033517	-0.045487	9.817970	0.044366	0.088066	-0.035839
+6.013238	-0.038305	-0.026334	9.786848	0.045299	0.088466	-0.037704
+6.014277	0.052669	-0.062245	9.791636	0.045299	0.089798	-0.041302
+6.015276	0.052669	-0.031123	9.762907	0.047430	0.090331	-0.036505
+6.016223	-0.023940	-0.004788	9.880215	0.045832	0.088466	-0.032775
+6.017272	0.052669	0.014364	9.899368	0.045032	0.085934	-0.032642
+6.018231	0.019152	-0.019152	9.880215	0.046764	0.087533	-0.032109
+6.019240	-0.028729	-0.028729	9.837123	0.045832	0.090997	-0.035173
+6.020235	0.028729	-0.023940	9.782060	0.046098	0.090464	-0.036505
+6.021276	0.021546	-0.021546	9.734179	0.046631	0.088199	-0.035706
+6.022279	0.043093	-0.031123	9.851487	0.046631	0.087666	-0.032642
+6.023278	0.026334	-0.002394	9.813182	0.045965	0.087266	-0.032775
+6.024272	-0.011970	0.004788	9.753331	0.046098	0.085668	-0.034907
+6.025274	-0.045487	-0.009576	9.846699	0.045432	0.088732	-0.035972
+6.026232	-0.052669	0.002394	9.832334	0.044766	0.090864	-0.034107
+6.027265	-0.045487	0.000000	9.748543	0.046231	0.089931	-0.038770
+6.028277	-0.023940	0.002394	9.750937	0.047297	0.089132	-0.039037
+6.029255	0.023940	0.076609	9.839517	0.048096	0.086867	-0.036905
+6.030278	0.016758	0.035911	9.837123	0.046498	0.085268	-0.036639
+6.031277	0.052669	0.033517	9.841911	0.049429	0.085668	-0.035839
+6.032277	0.038305	0.047881	9.815576	0.050495	0.084602	-0.036106
+6.033280	-0.007182	0.031123	9.762907	0.045832	0.086867	-0.033308
+6.034277	0.016758	0.057457	9.770089	0.043833	0.086600	-0.037172
+6.035247	-0.009576	0.000000	9.777271	0.044233	0.087000	-0.036505
+6.036269	0.002394	-0.028729	9.827546	0.047564	0.088199	-0.033441
+6.037262	0.002394	0.052669	9.774877	0.049029	0.086067	-0.035306
+6.038279	-0.031123	0.021546	9.794030	0.046897	0.085002	-0.038504
+6.039201	0.043093	0.000000	9.822758	0.046231	0.088599	-0.038904
+6.040182	0.031123	0.009576	9.853881	0.046897	0.090464	-0.035306
+6.041184	0.052669	0.007182	9.870639	0.047430	0.086734	-0.033841
+6.042202	0.004788	0.014364	9.777271	0.046631	0.088732	-0.035306
+6.043279	-0.011970	-0.016758	9.703056	0.046498	0.089531	-0.034907
+6.044279	0.021546	-0.038305	9.770089	0.045432	0.089665	-0.035972
+6.045275	0.055063	-0.038305	9.896974	0.045032	0.086600	-0.035040
+6.046271	0.062245	-0.038305	9.908944	0.045299	0.087000	-0.032775
+6.047247	0.031123	-0.033517	9.815576	0.046897	0.086467	-0.034240
+6.048260	-0.014364	-0.026334	9.710238	0.047164	0.084335	-0.038904
+6.049278	-0.014364	0.028729	9.695874	0.047430	0.087133	-0.040103
+6.050278	-0.009576	0.021546	9.789242	0.047031	0.087266	-0.038504
+6.051206	0.002394	0.021546	9.738967	0.047031	0.087000	-0.035706
+6.052275	-0.045487	0.009576	9.803606	0.049429	0.088066	-0.033041
+6.053275	-0.076609	0.009576	9.827546	0.048230	0.084069	-0.034773
+6.054279	0.019152	-0.011970	9.803606	0.048230	0.085401	-0.037704
+6.055276	0.050275	0.002394	9.865851	0.049429	0.088732	-0.037704
+6.056278	0.033517	-0.009576	9.832334	0.047297	0.090331	-0.038770
+6.057261	0.009576	0.045487	9.796424	0.043300	0.088732	-0.035040
+6.058303	-0.004788	0.043093	9.760513	0.043700	0.087000	-0.034507
+6.059266	-0.079003	0.004788	9.834729	0.046098	0.088466	-0.037038
+6.060258	-0.052669	-0.009576	9.748543	0.047430	0.088599	-0.036372
+6.061278	-0.055063	-0.050275	9.741361	0.047564	0.089531	-0.038104
+6.062280	0.047881	-0.023940	9.846699	0.045565	0.087933	-0.038637
+6.063277	0.052669	-0.002394	9.822758	0.043433	0.084868	-0.040369
+6.064277	0.067033	-0.031123	9.829940	0.044233	0.085534	-0.036505
+6.065280	0.045487	-0.021546	9.750937	0.047963	0.088199	-0.035573
+6.066255	0.002394	-0.014364	9.777271	0.050495	0.088865	-0.037971
+6.067272	0.004788	-0.076609	9.767695	0.050628	0.089931	-0.037305
+6.068212	0.026334	-0.076609	9.789242	0.049828	0.089398	-0.035573
+6.069250	0.019152	-0.047881	9.849093	0.048363	0.089398	-0.037704
+6.070276	0.009576	-0.062245	9.837123	0.046231	0.089398	-0.039037
+6.071277	0.021546	-0.035911	9.789242	0.045698	0.088466	-0.036505
+6.072277	-0.007182	-0.023940	9.868245	0.046897	0.087133	-0.034907
+6.073281	0.026334	-0.059851	9.796424	0.045165	0.086734	-0.034107
+6.074277	0.016758	-0.035911	9.825152	0.047164	0.087799	-0.031975
+6.075279	0.011970	-0.033517	9.870639	0.047564	0.090864	-0.038504
+6.076248	0.023940	0.016758	9.892186	0.047031	0.088865	-0.040636
+6.077309	0.033517	0.000000	9.841911	0.046631	0.088599	-0.037438
+6.078228	0.000000	0.035911	9.789242	0.049162	0.089931	-0.035040
+6.079276	-0.014364	-0.016758	9.794030	0.048896	0.087133	-0.034773
+6.080277	-0.014364	-0.014364	9.738967	0.043833	0.087133	-0.035306
+6.081275	0.031123	-0.031123	9.808394	0.043833	0.086600	-0.035972
+6.082277	0.031123	-0.035911	9.875427	0.045832	0.087400	-0.035306
+6.083274	-0.055063	-0.069427	9.806000	0.045698	0.088466	-0.033841
+6.084269	-0.081397	-0.011970	9.753331	0.046631	0.089132	-0.033974
+6.085228	-0.033517	0.007182	9.827546	0.047164	0.085534	-0.036372
+6.086237	0.040699	0.021546	9.820364	0.048496	0.085401	-0.038371
+6.087238	0.055063	-0.057457	9.865851	0.047830	0.087799	-0.037438
+6.088281	0.026334	-0.035911	9.877821	0.045299	0.088466	-0.035040
+6.089209	-0.002394	0.028729	9.791636	0.044632	0.089132	-0.036106
+6.090277	-0.031123	0.021546	9.777271	0.046098	0.088998	-0.037172
+6.091276	-0.033517	-0.019152	9.834729	0.048096	0.084735	-0.036372
+6.092276	-0.028729	-0.050275	9.861063	0.047830	0.085002	-0.038504
+6.093271	0.011970	-0.023940	9.899368	0.047830	0.085801	-0.036106
+6.094272	-0.002394	0.011970	9.899368	0.045965	0.086867	-0.033708
+6.095276	-0.021546	0.047881	9.760513	0.047430	0.091663	-0.036106
+6.096247	-0.021546	0.059851	9.803606	0.049296	0.092862	-0.038104
+6.097298	0.014364	-0.055063	9.815576	0.048629	0.092063	-0.035573
+6.098278	-0.016758	0.026334	9.758119	0.046631	0.086734	-0.036772
+6.099273	0.035911	0.009576	9.767695	0.047697	0.086600	-0.035573
+6.100277	0.019152	-0.023940	9.806000	0.049962	0.091130	-0.036106
+6.101276	0.043093	0.016758	9.774877	0.049962	0.089265	-0.034640
+6.102278	0.031123	0.052669	9.822758	0.047430	0.086600	-0.036106
+6.103275	0.021546	0.033517	9.813182	0.047297	0.086201	-0.034507
+6.104276	-0.057457	-0.031123	9.815576	0.046231	0.086867	-0.032109
+6.105278	-0.033517	0.033517	9.851487	0.045698	0.086600	-0.034507
+6.106250	-0.014364	-0.014364	9.841911	0.045698	0.086201	-0.035040
+6.107274	-0.009576	-0.002394	9.832334	0.045432	0.088199	-0.038237
+6.108252	0.002394	-0.016758	9.827546	0.046764	0.086734	-0.039570
+6.109245	0.050275	0.038305	9.896974	0.047564	0.085268	-0.036505
+6.110233	0.028729	-0.019152	9.846699	0.047297	0.082870	-0.035040
+6.111275	-0.002394	-0.040699	9.782060	0.045165	0.086600	-0.037571
+6.112276	-0.004788	-0.035911	9.750937	0.045565	0.090864	-0.036639
+6.113278	0.047881	-0.021546	9.827546	0.048363	0.092063	-0.036106
+6.114277	0.023940	-0.045487	9.853881	0.048363	0.089398	-0.034107
+6.115266	-0.047881	-0.011970	9.734179	0.045165	0.087666	-0.035972
+6.116292	0.009576	0.028729	9.717420	0.045299	0.089398	-0.037838
+6.117276	0.026334	-0.019152	9.820364	0.047697	0.089665	-0.035440
+6.118277	0.000000	-0.011970	9.837123	0.048230	0.088732	-0.034907
+6.119275	-0.038305	-0.009576	9.822758	0.048096	0.088466	-0.037305
+6.120270	-0.038305	0.014364	9.774877	0.047297	0.087666	-0.037704
+6.121276	0.026334	-0.007182	9.760513	0.046897	0.087000	-0.033841
+6.122262	0.000000	0.009576	9.707844	0.044499	0.089398	-0.032642
+6.123278	-0.004788	-0.064639	9.760513	0.044100	0.089132	-0.032642
+6.124271	-0.023940	-0.026334	9.798818	0.046631	0.088998	-0.032508
+6.125261	-0.002394	-0.055063	9.839517	0.048363	0.088998	-0.032242
+6.126277	0.009576	0.009576	9.782060	0.049029	0.088066	-0.034640
+6.127243	0.023940	0.045487	9.767695	0.048896	0.090997	-0.038237
+6.128274	-0.021546	0.059851	9.827546	0.047031	0.091796	-0.038770
+6.129275	0.009576	0.026334	9.810788	0.046364	0.089531	-0.036905
+6.130277	-0.002394	-0.011970	9.803606	0.047031	0.086867	-0.035706
+6.131274	0.043093	0.004788	9.875427	0.046764	0.087133	-0.035173
+6.132277	0.062245	-0.040699	9.865851	0.048896	0.088998	-0.032642
+6.133274	0.047881	0.028729	9.786848	0.048629	0.087799	-0.033441
+6.134276	0.076609	0.023940	9.810788	0.047963	0.085002	-0.035839
+6.135269	0.028729	0.059851	9.789242	0.048496	0.085934	-0.040902
+6.136304	-0.014364	-0.009576	9.820364	0.047697	0.088199	-0.040502
+6.137277	-0.019152	-0.033517	9.889792	0.044100	0.086201	-0.036772
+6.138213	0.033517	-0.011970	9.853881	0.044632	0.088865	-0.035573
+6.139276	0.023940	-0.026334	9.865851	0.045832	0.091263	-0.035173
+6.140215	0.069427	-0.064639	9.770089	0.046364	0.092196	-0.036639
+6.141272	0.057457	-0.038305	9.734179	0.046631	0.088865	-0.038371
+6.142272	0.047881	-0.057457	9.770089	0.044899	0.087533	-0.040636
+6.143274	-0.016758	-0.059851	9.767695	0.046231	0.090464	-0.041968
+6.144240	-0.016758	-0.011970	9.779666	0.047031	0.089531	-0.039170
+6.145249	-0.033517	-0.002394	9.762907	0.046897	0.090064	-0.033708
+6.146270	-0.014364	-0.035911	9.762907	0.048629	0.089931	-0.035040
+6.147274	-0.021546	-0.021546	9.743755	0.048230	0.087799	-0.037172
+6.148278	-0.007182	-0.038305	9.717420	0.047830	0.086201	-0.037438
+6.149277	0.000000	-0.004788	9.762907	0.046098	0.085401	-0.037038
+6.150276	0.014364	0.004788	9.743755	0.046631	0.085135	-0.037838
+6.151273	0.021546	0.033517	9.726997	0.047297	0.084735	-0.035839
+6.152243	0.028729	0.004788	9.808394	0.045565	0.084602	-0.035440
+6.153275	0.028729	-0.057457	9.810788	0.046098	0.087133	-0.036505
+6.154274	0.052669	-0.014364	9.880215	0.046231	0.088732	-0.037305
+6.155247	0.011970	-0.026334	9.870639	0.048363	0.091397	-0.034640
+6.156248	0.040699	0.011970	9.844305	0.048629	0.090198	-0.037038
+6.157276	0.086186	-0.038305	9.803606	0.047564	0.088332	-0.037571
+6.158277	0.038305	0.014364	9.844305	0.046231	0.088599	-0.039037
+6.159274	-0.007182	-0.009576	9.827546	0.044766	0.086867	-0.036639
+6.160273	0.026334	-0.033517	9.820364	0.044766	0.086600	-0.035306
+6.161265	0.002394	-0.016758	9.762907	0.045299	0.088865	-0.037305
+6.162274	0.004788	-0.007182	9.815576	0.046364	0.091663	-0.039836
+6.163273	-0.014364	-0.031123	9.817970	0.046897	0.091530	-0.038637
+6.164239	0.011970	-0.009576	9.849093	0.045832	0.087933	-0.034240
+6.165304	0.021546	-0.007182	9.810788	0.044632	0.085801	-0.032109
+6.166277	-0.019152	-0.038305	9.827546	0.046897	0.085268	-0.034507
+6.167274	-0.023940	-0.052669	9.825152	0.048496	0.087133	-0.034907
+6.168213	0.000000	-0.031123	9.858669	0.046897	0.088066	-0.035040
+6.169274	0.038305	-0.016758	9.741361	0.047164	0.088199	-0.036639
+6.170276	0.059851	0.007182	9.760513	0.048096	0.087799	-0.035440
+6.171277	-0.011970	0.004788	9.758119	0.045698	0.087933	-0.031709
+6.172276	-0.028729	0.004788	9.760513	0.042900	0.087400	-0.032775
+6.173275	0.009576	-0.009576	9.844305	0.046231	0.085534	-0.034907
+6.174248	0.007182	-0.081397	9.803606	0.048629	0.085934	-0.032775
+6.175273	0.002394	-0.026334	9.849093	0.047963	0.088199	-0.035972
+6.176275	-0.026334	0.007182	9.789242	0.046897	0.089665	-0.035972
+6.177240	0.000000	0.040699	9.806000	0.045832	0.089665	-0.033441
+6.178276	0.031123	0.023940	9.882609	0.048896	0.087933	-0.034374
+6.179272	-0.016758	-0.031123	9.923308	0.048363	0.087133	-0.036639
+6.180276	0.000000	-0.007182	9.746149	0.049695	0.088199	-0.039303
+6.181274	0.021546	0.031123	9.755725	0.046231	0.086201	-0.039170
+6.182275	0.007182	0.004788	9.794030	0.045698	0.088466	-0.035573
+6.183279	0.009576	0.000000	9.803606	0.044100	0.087266	-0.033974
+6.184252	0.019152	-0.038305	9.817970	0.044100	0.088066	-0.036905
+6.185216	0.026334	0.007182	9.880215	0.045165	0.088998	-0.040636
+6.186275	0.071821	-0.002394	9.870639	0.047564	0.089931	-0.037038
+6.187261	0.038305	0.007182	9.841911	0.047963	0.088332	-0.031975
+6.188642	0.023940	0.021546	9.832334	0.046897	0.089531	-0.031709
+6.189210	0.021546	0.004788	9.726997	0.043700	0.088199	-0.035706
+6.190275	-0.045487	0.014364	9.806000	0.044100	0.085002	-0.035706
+6.191274	-0.064639	0.007182	9.784454	0.047430	0.088066	-0.036505
+6.192274	0.009576	-0.026334	9.820364	0.049562	0.090064	-0.038371
+6.193276	0.026334	-0.047881	9.808394	0.048363	0.088865	-0.038237
+6.194215	0.045487	-0.021546	9.832334	0.045299	0.088998	-0.036106
+6.195278	0.011970	0.014364	9.865851	0.045299	0.085801	-0.037172
+6.196275	-0.002394	-0.038305	9.853881	0.048230	0.083802	-0.039303
+6.197275	0.057457	-0.055063	9.849093	0.047963	0.084602	-0.037704
+6.198270	0.074215	-0.011970	9.892186	0.047430	0.085934	-0.037571
+6.199259	0.004788	-0.028729	9.841911	0.045565	0.087133	-0.038770
+6.200275	-0.026334	-0.026334	9.817970	0.044899	0.089398	-0.037838
+6.201262	-0.002394	-0.002394	9.782060	0.045965	0.089398	-0.036106
+6.202270	-0.004788	-0.055063	9.846699	0.044499	0.088865	-0.036905
+6.203254	0.009576	-0.033517	9.791636	0.041835	0.086600	-0.036905
+6.204262	0.059851	-0.019152	9.719814	0.043034	0.087133	-0.036639
+6.205275	0.011970	-0.052669	9.703056	0.044899	0.089132	-0.036905
+6.206275	0.009576	0.004788	9.736573	0.047697	0.088199	-0.033974
+6.207240	-0.002394	-0.033517	9.703056	0.046764	0.088466	-0.035440
+6.208207	-0.002394	0.016758	9.834729	0.046764	0.089398	-0.037305
+6.209278	0.033517	-0.007182	9.825152	0.047297	0.088865	-0.037305
+6.210279	0.021546	-0.043093	9.858669	0.045965	0.087000	-0.036239
+6.211276	0.035911	0.009576	9.748543	0.047297	0.085934	-0.036772
+6.212274	0.062245	-0.004788	9.762907	0.048096	0.086201	-0.036372
+6.213245	-0.021546	0.038305	9.839517	0.046764	0.090331	-0.033574
+6.214233	-0.019152	0.057457	9.801212	0.046897	0.088998	-0.032775
+6.215276	0.016758	-0.004788	9.784454	0.048363	0.087133	-0.033974
+6.216276	-0.040699	-0.007182	9.822758	0.050228	0.088199	-0.037704
+6.217274	-0.031123	0.031123	9.748543	0.050361	0.088066	-0.036106
+6.218277	-0.043093	-0.023940	9.779666	0.046231	0.085534	-0.035839
+6.219271	-0.004788	0.016758	9.849093	0.044899	0.085401	-0.037438
+6.220274	-0.040699	0.035911	9.837123	0.043433	0.087133	-0.034773
+6.221274	-0.016758	0.031123	9.815576	0.045299	0.089531	-0.030643
+6.222276	-0.026334	-0.031123	9.767695	0.046631	0.089665	-0.033574
+6.223215	-0.007182	-0.069427	9.734179	0.045698	0.086867	-0.038104
+6.224257	0.040699	-0.055063	9.817970	0.044632	0.086201	-0.038371
+6.225296	0.023940	0.055063	9.815576	0.045965	0.090064	-0.033574
+6.226274	-0.023940	0.059851	9.813182	0.045832	0.090064	-0.032775
+6.227206	-0.052669	0.043093	9.846699	0.047697	0.088998	-0.035440
+6.228274	-0.069427	0.057457	9.803606	0.047963	0.088066	-0.037971
+6.229237	0.033517	-0.004788	9.834729	0.048896	0.090198	-0.039570
+6.230276	0.052669	-0.047881	9.827546	0.051161	0.088066	-0.040502
+6.231274	-0.023940	0.026334	9.822758	0.047031	0.086201	-0.037172
+6.232207	-0.014364	0.011970	9.820364	0.047564	0.086201	-0.035173
+6.233184	0.026334	-0.045487	9.753331	0.047963	0.084868	-0.035972
+6.234209	0.016758	-0.016758	9.894580	0.048230	0.086867	-0.040103
+6.235237	0.059851	0.031123	9.856275	0.048363	0.090597	-0.038504
+6.236210	0.019152	-0.016758	9.841911	0.047164	0.091263	-0.037038
+6.237276	0.019152	0.002394	9.837123	0.047697	0.089798	-0.036905
+6.238276	0.011970	-0.009576	9.755725	0.043833	0.088599	-0.035040
+6.239273	-0.004788	-0.026334	9.746149	0.045698	0.089398	-0.033841
+6.240274	0.023940	-0.016758	9.822758	0.047830	0.088998	-0.033308
+6.241274	0.026334	0.002394	9.798818	0.047830	0.089132	-0.033574
+6.242276	0.043093	-0.031123	9.820364	0.045965	0.089931	-0.034907
+6.243275	0.047881	-0.033517	9.798818	0.045565	0.088998	-0.035440
+6.244232	-0.028729	0.057457	9.748543	0.046498	0.085135	-0.037704
+6.245246	-0.028729	-0.007182	9.786848	0.044100	0.087533	-0.038371
+6.246271	0.002394	-0.074215	9.832334	0.043700	0.088865	-0.034240
+6.247273	-0.014364	-0.071821	9.837123	0.045698	0.088332	-0.035972
+6.248275	0.011970	-0.067033	9.817970	0.047697	0.085534	-0.037971
+6.249277	-0.004788	0.009576	9.806000	0.047830	0.083802	-0.040236
+6.250240	0.023940	-0.014364	9.801212	0.048896	0.084602	-0.038637
+6.251239	0.040699	-0.047881	9.825152	0.049162	0.086334	-0.038237
+6.252273	0.009576	-0.031123	9.856275	0.048363	0.088466	-0.035972
+6.253274	0.009576	-0.031123	9.856275	0.046897	0.088732	-0.035839
+6.254231	0.011970	-0.045487	9.849093	0.045032	0.087133	-0.034107
+6.255248	-0.019152	-0.016758	9.794030	0.043700	0.087533	-0.035173
+6.256275	-0.023940	0.009576	9.765301	0.043700	0.085534	-0.036905
+6.257276	-0.052669	-0.023940	9.822758	0.044632	0.086067	-0.035706
+6.258277	0.007182	0.026334	9.782060	0.047164	0.086734	-0.032109
+6.259210	-0.031123	0.043093	9.808394	0.047564	0.089132	-0.031309
+6.260220	0.002394	0.035911	9.806000	0.046098	0.089531	-0.035440
+6.261275	0.007182	-0.021546	9.762907	0.046498	0.088599	-0.036639
+6.262270	0.019152	-0.076609	9.789242	0.047564	0.085401	-0.036372
+6.263275	0.026334	-0.052669	9.837123	0.047297	0.086201	-0.038504
+6.264220	0.023940	0.007182	9.786848	0.048096	0.088998	-0.039969
+6.265275	0.021546	-0.007182	9.839517	0.048096	0.088865	-0.035573
+6.266276	-0.021546	-0.023940	9.784454	0.048363	0.087533	-0.035040
+6.267274	0.000000	0.009576	9.798818	0.046897	0.089665	-0.038237
+6.268273	0.016758	0.000000	9.832334	0.047031	0.089398	-0.039436
+6.269276	0.038305	-0.035911	9.772483	0.045698	0.089531	-0.037971
+6.270278	0.002394	-0.004788	9.786848	0.044766	0.088332	-0.039037
+6.271268	0.021546	-0.016758	9.786848	0.045299	0.086867	-0.038104
+6.272274	-0.014364	0.026334	9.810788	0.045299	0.085534	-0.037838
+6.273276	0.023940	0.009576	9.849093	0.044100	0.085668	-0.037571
+6.274220	-0.007182	-0.031123	9.827546	0.043034	0.085668	-0.031309
+6.275272	0.007182	0.000000	9.755725	0.043567	0.088332	-0.030910
+6.276275	0.052669	0.007182	9.746149	0.044899	0.090198	-0.036505
+6.277208	0.004788	-0.014364	9.803606	0.044499	0.088865	-0.040103
+6.278275	0.009576	-0.019152	9.822758	0.045165	0.086734	-0.038904
+6.279267	0.028729	-0.023940	9.746149	0.047430	0.084469	-0.039170
+6.280195	0.055063	0.009576	9.753331	0.048496	0.086600	-0.035839
+6.281184	0.038305	-0.023940	9.837123	0.048363	0.088599	-0.036239
+6.282185	0.011970	-0.014364	9.858669	0.048496	0.088466	-0.037172
+6.283183	-0.007182	-0.011970	9.798818	0.048096	0.086201	-0.034640
+6.284275	0.000000	-0.026334	9.815576	0.045965	0.087533	-0.033441
+6.285258	-0.016758	-0.047881	9.765301	0.047297	0.087133	-0.038104
+6.286259	0.009576	0.002394	9.782060	0.047164	0.088066	-0.040636
+6.287273	0.019152	0.011970	9.822758	0.048763	0.088865	-0.037571
+6.288256	0.002394	-0.021546	9.832334	0.049029	0.089798	-0.036106
+6.289203	-0.009576	0.016758	9.798818	0.047430	0.088732	-0.034374
+6.290184	-0.050275	0.009576	9.803606	0.045965	0.086600	-0.034374
+6.291184	-0.019152	-0.031123	9.734179	0.049029	0.087000	-0.036905
+6.292183	-0.019152	-0.004788	9.722208	0.047697	0.088732	-0.035706
+6.293178	-0.023940	0.002394	9.817970	0.045565	0.087400	-0.035706
+6.294179	-0.011970	0.028729	9.875427	0.045165	0.089798	-0.037438
+6.295183	0.009576	-0.035911	9.892186	0.044100	0.089798	-0.038371
+6.296183	-0.009576	-0.002394	9.817970	0.045165	0.088066	-0.035972
+6.297184	0.002394	0.014364	9.767695	0.046098	0.088199	-0.036372
+6.298183	0.011970	0.047881	9.875427	0.046364	0.086334	-0.036106
+6.299182	0.002394	0.002394	9.894580	0.047031	0.086600	-0.033041
+6.300184	0.004788	-0.081397	9.827546	0.047830	0.087933	-0.033974
+6.301182	0.011970	0.011970	9.710238	0.045299	0.090464	-0.034107
+6.302171	-0.011970	0.038305	9.820364	0.044499	0.090331	-0.036905
+6.303174	-0.009576	-0.009576	9.863457	0.044366	0.088199	-0.037172
+6.304201	0.016758	-0.021546	9.841911	0.048230	0.087400	-0.037971
+6.305258	-0.009576	-0.004788	9.853881	0.049296	0.086600	-0.038237
+6.306270	0.009576	-0.035911	9.784454	0.046897	0.086334	-0.038637
+6.307265	0.007182	0.026334	9.796424	0.045565	0.088332	-0.037438
+6.308265	-0.026334	0.019152	9.820364	0.048096	0.090864	-0.039303
+6.309266	-0.040699	-0.031123	9.820364	0.049296	0.088599	-0.038237
+6.310244	0.059851	0.007182	9.784454	0.047830	0.085801	-0.037438
+6.311274	-0.019152	-0.023940	9.806000	0.045698	0.088199	-0.038770
+6.312265	-0.011970	-0.014364	9.853881	0.044499	0.088998	-0.037971
+6.313266	0.004788	-0.011970	9.810788	0.047830	0.087000	-0.039170
+6.314269	-0.016758	-0.004788	9.813182	0.047564	0.086734	-0.038637
+6.315266	0.019152	-0.033517	9.801212	0.046631	0.086334	-0.035440
+6.316267	0.083792	0.004788	9.839517	0.046498	0.086600	-0.036372
+6.317260	0.062245	0.009576	9.808394	0.046364	0.086600	-0.037571
+6.318202	0.011970	0.016758	9.770089	0.047963	0.088732	-0.039037
+6.319265	0.011970	-0.050275	9.717420	0.047297	0.090997	-0.039436
+6.320240	0.016758	-0.043093	9.791636	0.046897	0.090730	-0.036239
+6.321214	0.045487	0.009576	9.815576	0.045832	0.089931	-0.036772
+6.322222	0.035911	0.050275	9.746149	0.048363	0.088865	-0.036239
+6.323269	0.000000	0.064639	9.803606	0.049162	0.089531	-0.035440
+6.324268	0.028729	0.023940	9.839517	0.048629	0.087400	-0.034907
+6.325265	0.059851	-0.016758	9.798818	0.047430	0.085002	-0.035040
+6.326263	0.055063	-0.055063	9.861063	0.048363	0.086201	-0.034773
+6.327198	-0.007182	0.016758	9.806000	0.050095	0.089132	-0.035706
+6.328220	0.023940	0.040699	9.844305	0.047963	0.088199	-0.034640
+6.329201	0.000000	0.019152	9.856275	0.046231	0.088199	-0.036639
+6.330261	-0.055063	0.016758	9.817970	0.049162	0.088332	-0.036905
+6.331263	-0.016758	-0.055063	9.688692	0.047430	0.088199	-0.036239
+6.332235	-0.031123	0.000000	9.731785	0.047031	0.088732	-0.037571
+6.333270	-0.009576	-0.026334	9.887397	0.046897	0.087266	-0.037305
+6.334270	-0.007182	-0.055063	9.868245	0.045832	0.088998	-0.035706
+6.335181	-0.028729	0.023940	9.772483	0.048496	0.090064	-0.037571
+6.336262	-0.007182	-0.026334	9.849093	0.049296	0.088865	-0.036772
+6.337266	-0.011970	-0.069427	9.885003	0.050361	0.087266	-0.034907
+6.338202	0.033517	-0.014364	9.837123	0.049562	0.088199	-0.033841
+6.339261	-0.019152	0.031123	9.801212	0.047031	0.090198	-0.033974
+6.340264	0.000000	-0.043093	9.846699	0.048230	0.089132	-0.036639
+6.341266	0.028729	-0.059851	9.889792	0.048763	0.089398	-0.040103
+6.342212	0.038305	-0.009576	9.851487	0.046897	0.088998	-0.040636
+6.343256	0.014364	0.023940	9.801212	0.045432	0.089665	-0.038904
+6.344262	0.009576	0.007182	9.782060	0.047564	0.089798	-0.035573
+6.345269	0.028729	-0.014364	9.806000	0.048096	0.089665	-0.035173
+6.346268	0.045487	-0.047881	9.806000	0.047830	0.089931	-0.035706
+6.347266	0.026334	0.011970	9.746149	0.045565	0.087400	-0.034640
+6.348260	0.035911	0.021546	9.767695	0.047297	0.086067	-0.035839
+6.349265	0.019152	0.009576	9.822758	0.048763	0.086867	-0.032908
+6.350265	-0.007182	0.028729	9.710238	0.047830	0.087666	-0.032508
+6.351250	-0.059851	0.000000	9.717420	0.045165	0.085002	-0.035440
+6.352236	-0.011970	-0.016758	9.784454	0.046498	0.085934	-0.037172
+6.353265	-0.016758	0.002394	9.760513	0.047963	0.088066	-0.037704
+6.354268	-0.016758	0.002394	9.808394	0.049695	0.088066	-0.037038
+6.355267	0.021546	0.021546	9.822758	0.047830	0.087933	-0.034773
+6.356267	-0.033517	0.023940	9.815576	0.048230	0.087000	-0.034107
+6.357265	0.031123	0.026334	9.834729	0.047564	0.086867	-0.036239
+6.358268	0.043093	0.038305	9.844305	0.045965	0.089132	-0.039836
+6.359265	0.014364	0.028729	9.801212	0.044899	0.089798	-0.039969
+6.360239	-0.016758	0.052669	9.846699	0.045432	0.088332	-0.035440
+6.361271	-0.035911	0.040699	9.782060	0.045965	0.086600	-0.032775
+6.362226	-0.069427	0.019152	9.715026	0.046498	0.086734	-0.033708
+6.363267	0.014364	-0.014364	9.779666	0.044233	0.084868	-0.036372
+6.364264	-0.007182	-0.040699	9.784454	0.046631	0.088466	-0.037172
+6.365260	-0.016758	0.033517	9.825152	0.048763	0.090331	-0.041302
+6.366268	0.009576	0.059851	9.825152	0.049296	0.089931	-0.041701
+6.367264	-0.011970	0.052669	9.894580	0.046498	0.086867	-0.038770
+6.368202	-0.002394	0.011970	9.820364	0.047164	0.084602	-0.037038
+6.369267	0.026334	-0.021546	9.774877	0.048096	0.086334	-0.033441
+6.370266	0.023940	0.021546	9.760513	0.049695	0.090331	-0.032242
+6.371258	0.021546	0.002394	9.738967	0.047297	0.088599	-0.033574
+6.372262	0.019152	0.026334	9.772483	0.046364	0.088599	-0.035573
+6.373266	0.004788	0.031123	9.904156	0.045432	0.091663	-0.036239
+6.374262	-0.038305	-0.062245	9.844305	0.049029	0.090864	-0.035839
+6.375265	-0.014364	-0.062245	9.784454	0.050095	0.087400	-0.033974
+6.376266	0.035911	-0.031123	9.786848	0.048230	0.084602	-0.035173
+6.377266	-0.009576	-0.021546	9.779666	0.045965	0.086867	-0.034640
+6.378225	0.004788	-0.004788	9.846699	0.047164	0.088466	-0.035040
+6.379215	0.004788	0.026334	9.868245	0.045965	0.088599	-0.036505
+6.380265	-0.004788	0.040699	9.875427	0.045432	0.088199	-0.035173
+6.381209	0.031123	-0.011970	9.810788	0.047164	0.086867	-0.036905
+6.382230	0.014364	-0.040699	9.789242	0.046897	0.085934	-0.036106
+6.383208	-0.067033	0.011970	9.870639	0.046364	0.087266	-0.037172
+6.384205	-0.007182	-0.007182	9.894580	0.046231	0.088332	-0.038770
+6.385254	-0.014364	-0.011970	9.849093	0.046364	0.088332	-0.038371
+6.386267	0.040699	-0.043093	9.786848	0.047697	0.089265	-0.039170
+6.387264	0.019152	-0.033517	9.767695	0.047697	0.088199	-0.039570
+6.388249	0.009576	0.019152	9.815576	0.045432	0.087000	-0.037971
+6.389201	0.019152	-0.043093	9.920914	0.044899	0.089798	-0.032642
+6.390264	0.019152	-0.035911	9.892186	0.045832	0.088865	-0.032642
+6.391228	-0.009576	-0.016758	9.856275	0.044100	0.089265	-0.038504
+6.392208	0.000000	0.016758	9.782060	0.045165	0.088466	-0.038770
+6.393194	0.019152	0.009576	9.746149	0.046764	0.088466	-0.036905
+6.394179	-0.016758	-0.002394	9.810788	0.048096	0.088199	-0.035706
+6.395214	-0.043093	0.000000	9.782060	0.048096	0.083536	-0.035706
+6.396196	-0.047881	0.019152	9.748543	0.046897	0.082470	-0.036505
+6.397199	-0.021546	0.028729	9.856275	0.047564	0.085801	-0.036772
+6.398200	-0.038305	0.011970	9.827546	0.049029	0.088998	-0.036639
+6.399215	-0.040699	0.014364	9.839517	0.047697	0.088599	-0.038237
+6.400267	0.002394	0.004788	9.767695	0.047564	0.088732	-0.035040
+6.401266	-0.047881	-0.021546	9.810788	0.048230	0.087000	-0.036505
+6.402224	-0.040699	-0.004788	9.755725	0.044766	0.087400	-0.039436
+6.403273	0.026334	-0.040699	9.695874	0.043300	0.090464	-0.037838
+6.404273	-0.002394	-0.026334	9.753331	0.046498	0.090198	-0.035706
+6.405245	-0.021546	-0.004788	9.772483	0.047297	0.087933	-0.033708
+6.406260	0.002394	0.021546	9.789242	0.045698	0.087266	-0.033175
+6.407239	-0.021546	0.023940	9.894580	0.044233	0.086334	-0.036106
+6.408296	-0.009576	-0.002394	9.746149	0.046364	0.088865	-0.039570
+6.409262	-0.011970	-0.031123	9.738967	0.047164	0.087533	-0.040636
+6.410210	0.000000	-0.026334	9.729391	0.047963	0.085002	-0.038104
+6.411273	-0.040699	0.007182	9.753331	0.047297	0.087000	-0.037704
+6.412275	0.004788	-0.009576	9.760513	0.046631	0.091130	-0.036239
+6.413273	0.016758	0.009576	9.796424	0.046498	0.091530	-0.037305
+6.414276	-0.019152	-0.067033	9.868245	0.046498	0.088066	-0.039303
+6.415271	0.009576	0.000000	9.849093	0.047031	0.087400	-0.039037
+6.416240	0.023940	0.002394	9.794030	0.045698	0.086067	-0.034907
+6.417255	0.004788	0.052669	9.817970	0.042501	0.087533	-0.033841
+6.418216	-0.043093	0.007182	9.808394	0.046231	0.090597	-0.035306
+6.419262	0.007182	-0.016758	9.877821	0.045165	0.090730	-0.038237
+6.420274	-0.007182	-0.038305	9.863457	0.045832	0.088066	-0.037971
+6.421273	0.009576	0.000000	9.839517	0.044766	0.087933	-0.035839
+6.422274	-0.011970	0.000000	9.925702	0.045165	0.088199	-0.035173
+6.423274	-0.007182	0.007182	9.806000	0.047164	0.088732	-0.037704
+6.424273	0.002394	0.002394	9.801212	0.049296	0.089798	-0.036905
+6.425272	-0.023940	-0.002394	9.794030	0.046231	0.088332	-0.033441
+6.426245	0.000000	0.016758	9.810788	0.046364	0.089132	-0.033974
+6.427270	-0.045487	-0.062245	9.798818	0.045432	0.087666	-0.038637
+6.428218	0.000000	-0.069427	9.784454	0.045299	0.086467	-0.038371
+6.429236	0.016758	-0.045487	9.803606	0.045432	0.086067	-0.034773
+6.430273	-0.028729	-0.023940	9.753331	0.044766	0.088599	-0.034640
+6.431271	0.040699	-0.040699	9.712632	0.046098	0.089798	-0.035972
+6.432272	0.002394	-0.009576	9.748543	0.045432	0.087799	-0.035972
+6.433273	-0.009576	-0.002394	9.794030	0.044100	0.085002	-0.039436
+6.434273	-0.035911	0.014364	9.832334	0.045165	0.082337	-0.039570
+6.435232	-0.011970	-0.002394	9.755725	0.046631	0.083003	-0.037438
+6.436269	0.021546	-0.016758	9.815576	0.049029	0.084868	-0.039436
+6.437301	0.031123	-0.023940	9.813182	0.050495	0.085401	-0.038904
+6.438274	0.035911	-0.019152	9.880215	0.047697	0.085801	-0.037571
+6.439273	-0.031123	-0.014364	9.791636	0.046498	0.084602	-0.033708
+6.440268	-0.038305	0.000000	9.794030	0.044233	0.084202	-0.035173
+6.441270	0.021546	0.023940	9.825152	0.044766	0.089398	-0.038371
+6.442273	0.000000	0.007182	9.794030	0.045432	0.090997	-0.040502
+6.443271	-0.021546	0.026334	9.817970	0.045965	0.087799	-0.036639
+6.444267	-0.045487	0.007182	9.760513	0.046498	0.085801	-0.036372
+6.445272	0.011970	-0.021546	9.815576	0.046364	0.088199	-0.037438
+6.446272	-0.009576	0.002394	9.832334	0.045299	0.090597	-0.038637
+6.447262	-0.026334	0.028729	9.817970	0.044766	0.091530	-0.036106
+6.448272	0.002394	0.023940	9.832334	0.047963	0.089531	-0.036372
+6.449238	-0.004788	0.000000	9.813182	0.050761	0.086734	-0.038770
+6.450209	0.016758	-0.035911	9.729391	0.049296	0.087000	-0.036505
+6.451194	0.040699	-0.071821	9.772483	0.046764	0.090331	-0.035972
+6.452274	-0.004788	-0.009576	9.772483	0.044899	0.090864	-0.036106
+6.453268	0.031123	-0.028729	9.868245	0.045698	0.089931	-0.037838
+6.454273	0.009576	-0.081397	9.880215	0.046631	0.089665	-0.038637
+6.455274	0.057457	-0.011970	9.746149	0.045965	0.088199	-0.038504
+6.456245	0.088580	-0.004788	9.782060	0.046631	0.087533	-0.034507
+6.457309	0.059851	-0.016758	9.794030	0.044766	0.087400	-0.035173
+6.458187	0.014364	0.014364	9.782060	0.046897	0.088332	-0.036772
+6.459273	0.050275	-0.026334	9.734179	0.048096	0.086867	-0.035839
+6.460273	0.083792	-0.040699	9.825152	0.047031	0.085268	-0.036372
+6.461274	0.019152	-0.014364	9.758119	0.046764	0.085534	-0.034107
+6.462275	-0.007182	0.011970	9.841911	0.044632	0.087533	-0.036106
+6.463272	0.011970	0.016758	9.846699	0.043300	0.091263	-0.033974
+6.464272	0.009576	0.011970	9.803606	0.043433	0.092063	-0.035706
+6.465274	0.009576	0.004788	9.846699	0.046498	0.088599	-0.039037
+6.466243	0.026334	-0.004788	9.841911	0.045832	0.087133	-0.039303
+6.467301	0.004788	-0.040699	9.892186	0.044766	0.087133	-0.035706
+6.468253	-0.052669	-0.004788	9.758119	0.045032	0.088998	-0.032109
+6.469269	-0.019152	-0.035911	9.827546	0.047297	0.087266	-0.035706
+6.470275	0.021546	-0.031123	9.877821	0.047164	0.086867	-0.036905
+6.471273	0.009576	-0.064639	9.875427	0.045965	0.087799	-0.036905
+6.472269	-0.043093	-0.007182	9.832334	0.047164	0.089265	-0.036905
+6.473275	-0.038305	0.002394	9.870639	0.047564	0.089931	-0.036772
+6.474266	-0.011970	0.019152	9.772483	0.047031	0.086734	-0.036905
+6.475273	0.004788	0.007182	9.817970	0.045965	0.085668	-0.037172
+6.476245	-0.028729	0.045487	9.873033	0.045165	0.087933	-0.036106
+6.477221	-0.043093	0.035911	9.784454	0.047297	0.089398	-0.034907
+6.478246	0.016758	0.026334	9.789242	0.047430	0.088599	-0.035839
+6.479273	0.007182	0.033517	9.743755	0.045299	0.088066	-0.036106
+6.480267	0.033517	-0.016758	9.758119	0.044899	0.086067	-0.034907
+6.481274	0.019152	-0.035911	9.748543	0.048629	0.088732	-0.031176
+6.482274	0.057457	-0.014364	9.794030	0.049695	0.090198	-0.035040
+6.483268	0.014364	-0.009576	9.851487	0.047830	0.088466	-0.038237
+6.484203	0.014364	-0.040699	9.798818	0.047564	0.088332	-0.040369
+6.485175	-0.028729	-0.009576	9.779666	0.045832	0.088998	-0.036239
+6.486235	0.016758	0.016758	9.849093	0.044632	0.087400	-0.035040
+6.487269	0.043093	-0.007182	9.858669	0.043567	0.088066	-0.036505
+6.488216	-0.004788	0.071821	9.782060	0.047963	0.087666	-0.035040
+6.489269	-0.004788	-0.004788	9.810788	0.048230	0.085801	-0.033441
+6.490276	-0.014364	-0.067033	9.760513	0.048230	0.089265	-0.037038
+6.491273	0.009576	-0.047881	9.760513	0.049162	0.089132	-0.039436
+6.492255	0.021546	0.028729	9.861063	0.047297	0.091530	-0.035440
+6.493231	-0.007182	-0.026334	9.858669	0.044366	0.090064	-0.036106
+6.494243	0.002394	-0.009576	9.777271	0.043433	0.088466	-0.032775
+6.495242	-0.004788	-0.028729	9.827546	0.046764	0.086467	-0.034240
+6.496242	-0.040699	-0.011970	9.858669	0.048230	0.086201	-0.035839
+6.497270	-0.019152	0.031123	9.868245	0.046631	0.088466	-0.035839
+6.498299	0.035911	0.023940	9.808394	0.045832	0.089665	-0.037838
+6.499272	0.033517	0.002394	9.839517	0.045565	0.088998	-0.033574
+6.500274	-0.004788	-0.038305	9.817970	0.044100	0.087266	-0.031043
+6.501275	0.011970	-0.031123	9.896974	0.046098	0.086334	-0.031975
+6.502271	0.002394	0.007182	9.803606	0.046364	0.087533	-0.034773
+6.503273	0.033517	0.064639	9.820364	0.045299	0.086734	-0.035972
+6.504273	0.035911	-0.004788	9.877821	0.046231	0.087933	-0.035706
+6.505276	0.064639	-0.004788	9.870639	0.045165	0.090331	-0.033041
+6.506275	-0.014364	-0.014364	9.774877	0.046364	0.089531	-0.032775
+6.507267	-0.026334	-0.021546	9.722208	0.047963	0.085934	-0.033574
+6.508268	0.011970	-0.038305	9.738967	0.049162	0.085668	-0.033841
+6.509273	0.047881	0.002394	9.748543	0.049162	0.089398	-0.036505
+6.510258	0.023940	0.019152	9.810788	0.048230	0.089931	-0.036905
+6.511272	-0.016758	0.014364	9.837123	0.046364	0.089665	-0.036372
+6.512270	0.028729	0.045487	9.772483	0.046098	0.088599	-0.036505
+6.513266	0.026334	0.038305	9.813182	0.048763	0.088998	-0.038104
+6.514274	0.011970	-0.002394	9.738967	0.049429	0.088998	-0.035839
+6.515273	0.009576	-0.040699	9.748543	0.044766	0.090331	-0.033041
+6.516241	0.055063	-0.059851	9.810788	0.044766	0.088199	-0.030643
+6.517221	0.028729	-0.081397	9.801212	0.044632	0.086734	-0.033974
+6.518174	-0.014364	0.004788	9.810788	0.046631	0.086600	-0.039303
+6.519272	0.035911	0.023940	9.817970	0.049429	0.087933	-0.043433
+6.520258	0.059851	0.009576	9.865851	0.048896	0.088066	-0.038237
+6.521272	0.011970	0.007182	9.844305	0.050095	0.088865	-0.035839
+6.522273	-0.009576	0.011970	9.875427	0.049296	0.084868	-0.035972
+6.523271	0.033517	0.014364	9.777271	0.049695	0.085801	-0.037971
+6.524271	0.021546	0.043093	9.853881	0.049162	0.089398	-0.035972
+6.525272	0.090974	0.067033	9.908944	0.048230	0.089665	-0.034907
+6.526240	0.023940	0.014364	9.796424	0.047830	0.087933	-0.035440
+6.527217	0.067033	0.004788	9.784454	0.046364	0.088332	-0.036106
+6.528222	0.031123	0.014364	9.760513	0.045165	0.088865	-0.036905
+6.529228	0.011970	-0.038305	9.817970	0.045032	0.084602	-0.034773
+6.530233	-0.011970	-0.028729	9.832334	0.048363	0.085801	-0.034640
+6.531267	-0.002394	0.009576	9.786848	0.046498	0.087133	-0.035306
+6.532197	0.040699	0.021546	9.746149	0.046231	0.088466	-0.035972
+6.533272	-0.026334	0.004788	9.741361	0.049029	0.090331	-0.036239
+6.534272	0.004788	-0.009576	9.738967	0.048629	0.088332	-0.037038
+6.535209	-0.019152	0.023940	9.837123	0.049562	0.088066	-0.036905
+6.536272	0.038305	0.014364	9.813182	0.048363	0.089132	-0.035706
+6.537258	0.021546	-0.009576	9.762907	0.048763	0.088332	-0.039037
+6.538225	0.088580	-0.019152	9.707844	0.048763	0.088199	-0.040369
+6.539271	0.023940	-0.026334	9.760513	0.049296	0.087266	-0.037704
+6.540271	0.014364	0.002394	9.918520	0.048096	0.088466	-0.035440
+6.541272	-0.043093	0.038305	9.899368	0.049429	0.087666	-0.037704
+6.542273	-0.019152	0.040699	9.832334	0.047430	0.087533	-0.036772
+6.543267	-0.004788	0.023940	9.726997	0.046364	0.087266	-0.033841
+6.544270	0.045487	-0.074215	9.738967	0.045965	0.088332	-0.033974
+6.545272	0.021546	-0.067033	9.734179	0.045832	0.088199	-0.032508
+6.546274	-0.002394	-0.004788	9.834729	0.046897	0.087933	-0.035040
+6.547255	-0.016758	0.014364	9.841911	0.047697	0.088066	-0.034374
+6.548288	0.000000	-0.009576	9.815576	0.045299	0.091663	-0.035173
+6.549255	0.011970	-0.023940	9.760513	0.046098	0.091130	-0.037838
+6.550214	-0.016758	-0.031123	9.810788	0.047430	0.087933	-0.038904
+6.551213	0.047881	0.000000	9.894580	0.047963	0.086467	-0.038504
+6.552272	0.040699	-0.002394	9.796424	0.046764	0.087799	-0.035972
+6.553230	0.021546	-0.016758	9.794030	0.048363	0.089798	-0.035706
+6.554276	0.016758	0.035911	9.791636	0.048629	0.089398	-0.037305
+6.555271	0.002394	0.009576	9.796424	0.048496	0.088732	-0.036239
+6.556272	-0.023940	-0.043093	9.815576	0.048896	0.087799	-0.035573
+6.557265	-0.040699	-0.079003	9.789242	0.047031	0.087933	-0.038371
+6.558220	-0.031123	0.011970	9.746149	0.045698	0.084335	-0.037838
+6.559254	-0.028729	0.004788	9.782060	0.045165	0.084868	-0.035573
+6.560270	-0.026334	-0.031123	9.880215	0.048096	0.088599	-0.036106
+6.561273	-0.002394	-0.009576	9.908944	0.045965	0.090597	-0.033974
+6.562268	-0.004788	-0.004788	9.849093	0.045698	0.087266	-0.034640
+6.563271	0.023940	-0.038305	9.817970	0.045832	0.087533	-0.037038
+6.564271	0.011970	-0.028729	9.755725	0.046764	0.087000	-0.037571
+6.565266	-0.002394	-0.009576	9.717420	0.047031	0.086467	-0.036505
+6.566269	-0.055063	0.009576	9.762907	0.045165	0.084202	-0.036639
+6.567240	0.004788	0.011970	9.750937	0.044366	0.085801	-0.035839
+6.568195	0.021546	0.019152	9.770089	0.045965	0.089265	-0.038504
+6.569296	-0.028729	0.031123	9.856275	0.047430	0.090198	-0.036639
+6.570272	-0.023940	-0.031123	9.853881	0.048763	0.091130	-0.035972
+6.571271	0.004788	0.031123	9.748543	0.045965	0.088732	-0.038904
+6.572270	-0.002394	0.021546	9.774877	0.043167	0.086600	-0.036505
+6.573272	-0.035911	-0.038305	9.803606	0.046098	0.086334	-0.033708
+6.574272	-0.011970	-0.059851	9.767695	0.048230	0.087133	-0.034507
+6.575271	-0.031123	0.002394	9.803606	0.047164	0.085934	-0.038904
+6.576269	0.026334	0.028729	9.810788	0.044899	0.085801	-0.037038
+6.577273	0.069427	0.014364	9.829940	0.045965	0.088998	-0.038104
+6.578212	0.007182	-0.052669	9.736573	0.048363	0.088865	-0.036106
+6.579243	-0.023940	-0.021546	9.717420	0.046897	0.086467	-0.035972
+6.580271	-0.026334	0.026334	9.705450	0.049029	0.085801	-0.038371
+6.581272	-0.021546	0.021546	9.777271	0.049828	0.088199	-0.035706
+6.582274	-0.007182	-0.014364	9.796424	0.046098	0.089132	-0.035972
+6.583271	-0.035911	0.009576	9.851487	0.047031	0.085135	-0.037438
+6.584264	-0.031123	0.045487	9.760513	0.049162	0.085135	-0.036106
+6.585243	-0.038305	0.031123	9.853881	0.048230	0.087799	-0.035173
+6.586272	-0.011970	0.028729	9.784454	0.045965	0.089398	-0.034240
+6.587207	0.002394	0.002394	9.724603	0.046764	0.087533	-0.037172
+6.588244	-0.004788	0.016758	9.762907	0.048363	0.088732	-0.035173
+6.589255	0.033517	0.059851	9.767695	0.048363	0.088332	-0.034773
+6.590219	0.033517	-0.002394	9.798818	0.047564	0.087400	-0.035972
+6.591271	0.031123	0.000000	9.863457	0.047697	0.086867	-0.036505
+6.592273	0.055063	-0.007182	9.762907	0.048230	0.086067	-0.035040
+6.593270	-0.014364	-0.050275	9.762907	0.047031	0.086067	-0.033175
+6.594271	-0.043093	0.002394	9.770089	0.045965	0.089531	-0.031576
+6.595216	-0.011970	-0.023940	9.774877	0.047830	0.092063	-0.032242
+6.596259	-0.019152	-0.009576	9.837123	0.048629	0.089132	-0.036505
+6.597271	0.009576	-0.016758	9.861063	0.045832	0.086600	-0.036639
+6.598269	0.000000	-0.033517	9.803606	0.045299	0.087666	-0.034773
+6.599224	0.000000	-0.038305	9.786848	0.045299	0.087266	-0.034240
+6.600290	0.002394	-0.033517	9.810788	0.045032	0.089398	-0.036239
+6.601272	0.009576	-0.019152	9.801212	0.047297	0.089798	-0.037838
+6.602271	-0.002394	0.000000	9.765301	0.047564	0.087000	-0.037838
+6.603269	-0.007182	-0.016758	9.729391	0.049029	0.085934	-0.036772
+6.604265	-0.035911	0.028729	9.806000	0.046764	0.086334	-0.032642
+6.605272	-0.047881	0.004788	9.868245	0.047830	0.087799	-0.034107
+6.606272	-0.043093	0.043093	9.832334	0.047297	0.090730	-0.038104
+6.607261	-0.007182	-0.031123	9.827546	0.046631	0.086467	-0.039436
+6.608273	0.002394	-0.081397	9.772483	0.048763	0.083403	-0.036372
+6.609211	0.004788	-0.045487	9.784454	0.049429	0.083936	-0.034907
+6.610191	0.028729	0.031123	9.808394	0.046897	0.084202	-0.033708
+6.611218	-0.043093	0.028729	9.822758	0.043833	0.088599	-0.035706
+6.612218	-0.038305	-0.009576	9.815576	0.044899	0.090464	-0.036639
+6.613218	-0.004788	-0.052669	9.760513	0.046498	0.088599	-0.037838
+6.614219	0.014364	-0.047881	9.825152	0.047164	0.085268	-0.040502
+6.615218	-0.031123	-0.002394	9.856275	0.047564	0.086600	-0.039303
+6.616219	-0.047881	0.069427	9.806000	0.047830	0.088066	-0.033574
+6.617220	0.028729	-0.014364	9.906550	0.048363	0.088466	-0.030110
+6.618249	0.026334	0.007182	9.829940	0.046364	0.089132	-0.034240
+6.619235	0.016758	-0.002394	9.875427	0.047297	0.089132	-0.037571
+6.620271	0.035911	0.021546	9.784454	0.048096	0.087799	-0.036239
+6.621257	0.052669	0.033517	9.722208	0.048363	0.085268	-0.035440
+6.622281	-0.011970	-0.055063	9.753331	0.048496	0.086467	-0.035972
+6.623272	0.009576	-0.069427	9.815576	0.048230	0.087933	-0.040103
+6.624272	0.002394	-0.007182	9.820364	0.047963	0.088332	-0.038637
+6.625272	-0.031123	-0.002394	9.786848	0.047430	0.087266	-0.035706
+6.626273	0.007182	0.014364	9.777271	0.045965	0.085801	-0.037571
+6.627270	0.059851	0.038305	9.731785	0.046498	0.086867	-0.038237
+6.628203	0.062245	-0.011970	9.770089	0.047963	0.088466	-0.036239
+6.629218	0.019152	-0.031123	9.801212	0.044766	0.090730	-0.035306
+6.630284	0.021546	-0.021546	9.789242	0.044233	0.089931	-0.035173
+6.631256	0.016758	0.011970	9.741361	0.046631	0.090997	-0.033974
+6.632266	0.016758	0.040699	9.736573	0.048363	0.090331	-0.034240
+6.633272	0.028729	0.079003	9.856275	0.048496	0.091930	-0.033574
+6.634272	0.002394	0.023940	9.820364	0.048096	0.090064	-0.033974
+6.635245	0.043093	0.004788	9.746149	0.047564	0.089265	-0.034107
+6.636238	0.007182	0.038305	9.726997	0.048096	0.088066	-0.035706
+6.637239	-0.002394	-0.002394	9.743755	0.047297	0.088066	-0.036106
+6.638240	0.028729	-0.016758	9.765301	0.046231	0.089531	-0.037704
+6.639271	0.016758	-0.009576	9.767695	0.045565	0.092196	-0.035706
+6.640271	-0.019152	0.031123	9.798818	0.047297	0.088332	-0.034507
+6.641271	0.009576	0.016758	9.975977	0.047564	0.087000	-0.035040
+6.642243	0.019152	-0.002394	9.834729	0.046897	0.086334	-0.037172
+6.643266	-0.002394	-0.040699	9.832334	0.046231	0.086734	-0.033308
+6.644269	0.014364	-0.038305	9.815576	0.047164	0.089531	-0.034374
+6.645271	0.002394	0.019152	9.815576	0.044499	0.088332	-0.037838
+6.646271	0.026334	0.055063	9.784454	0.042501	0.085268	-0.036772
+6.647268	0.033517	-0.033517	9.765301	0.045565	0.084602	-0.035040
+6.648269	0.016758	-0.019152	9.767695	0.049962	0.087533	-0.033574
+6.649273	0.000000	-0.047881	9.753331	0.049695	0.090198	-0.036905
+6.650239	-0.040699	-0.064639	9.705450	0.046098	0.090331	-0.033708
+6.651237	-0.014364	-0.009576	9.825152	0.046897	0.088865	-0.032908
+6.652243	0.004788	0.045487	9.829940	0.047430	0.088332	-0.035040
+6.653259	-0.007182	-0.011970	9.803606	0.048230	0.088066	-0.037305
+6.654273	-0.002394	-0.014364	9.734179	0.047830	0.089531	-0.037172
+6.655244	0.002394	0.000000	9.707844	0.047697	0.089531	-0.032242
+6.656239	-0.016758	-0.050275	9.798818	0.049162	0.091397	-0.034107
+6.657272	0.009576	-0.067033	9.896974	0.047430	0.090464	-0.036905
+6.658215	0.023940	-0.014364	9.794030	0.046498	0.087133	-0.035706
+6.659200	-0.011970	-0.002394	9.822758	0.048363	0.083936	-0.034907
+6.660204	0.016758	0.007182	9.806000	0.047564	0.086334	-0.036372
+6.661220	-0.002394	0.007182	9.832334	0.046231	0.089132	-0.034374
+6.662222	0.007182	0.014364	9.822758	0.045832	0.086334	-0.033574
+6.663267	-0.002394	-0.011970	9.770089	0.047031	0.087533	-0.036905
+6.664271	-0.004788	-0.047881	9.681510	0.043700	0.088199	-0.037971
+6.665271	-0.007182	0.002394	9.808394	0.045032	0.089132	-0.036239
+6.666235	0.040699	0.007182	9.815576	0.046897	0.087400	-0.037571
+6.667207	0.035911	0.007182	9.767695	0.046231	0.086201	-0.035573
+6.668212	-0.031123	-0.038305	9.798818	0.045965	0.085401	-0.031443
+6.669271	0.000000	-0.019152	9.813182	0.045165	0.087533	-0.034240
+6.670271	-0.004788	0.011970	9.743755	0.048230	0.088732	-0.036639
+6.671227	0.035911	-0.067033	9.791636	0.047830	0.088066	-0.033974
+6.672290	0.043093	-0.050275	9.760513	0.047963	0.089665	-0.036505
+6.673272	0.011970	-0.002394	9.695874	0.046498	0.089665	-0.039303
+6.674266	0.033517	0.031123	9.849093	0.047164	0.089531	-0.039969
+6.675271	-0.026334	-0.007182	9.772483	0.046364	0.090597	-0.036639
+6.676270	-0.011970	0.011970	9.784454	0.046098	0.091263	-0.033574
+6.677271	-0.016758	0.016758	9.829940	0.046631	0.089398	-0.036106
+6.678204	-0.067033	0.033517	9.741361	0.049029	0.086467	-0.037038
+6.679204	0.047881	-0.002394	9.758119	0.047830	0.088066	-0.039037
+6.680271	-0.007182	-0.019152	9.794030	0.045832	0.088199	-0.035306
+6.681255	-0.038305	-0.009576	9.750937	0.047164	0.088599	-0.032242
+6.682276	0.019152	0.011970	9.750937	0.047564	0.088199	-0.036239
+6.683264	0.055063	0.000000	9.731785	0.049296	0.088865	-0.036772
+6.684270	0.074215	-0.057457	9.870639	0.048096	0.091263	-0.037305
+6.685210	0.002394	-0.031123	9.851487	0.045432	0.089665	-0.035839
+6.686272	-0.031123	-0.004788	9.837123	0.045965	0.089398	-0.037704
+6.687269	0.011970	0.019152	9.839517	0.044499	0.086734	-0.035972
+6.688253	-0.067033	-0.016758	9.839517	0.047564	0.085268	-0.035706
+6.689249	-0.007182	-0.055063	9.834729	0.049296	0.086600	-0.039170
+6.690270	0.021546	-0.055063	9.918520	0.047430	0.087133	-0.039570
+6.691275	0.069427	0.002394	9.856275	0.044499	0.087133	-0.039836
+6.692220	0.028729	-0.045487	9.813182	0.044632	0.087133	-0.038371
+6.693268	-0.031123	-0.002394	9.892186	0.048896	0.089665	-0.039836
+6.694271	0.004788	-0.035911	9.906550	0.049162	0.090997	-0.036106
+6.695269	0.014364	-0.023940	9.808394	0.049429	0.089798	-0.032242
+6.696212	0.016758	0.035911	9.784454	0.047297	0.087933	-0.036905
+6.697270	0.016758	0.026334	9.829940	0.045832	0.087933	-0.039436
+6.698227	0.057457	-0.011970	9.853881	0.048096	0.090331	-0.039037
+6.699244	-0.043093	-0.026334	9.796424	0.047430	0.090331	-0.036905
+6.700265	-0.007182	-0.004788	9.844305	0.047031	0.088599	-0.036372
+6.701237	0.021546	-0.009576	9.844305	0.045698	0.087666	-0.035839
+6.702212	0.035911	-0.045487	9.789242	0.047430	0.087933	-0.034907
+6.703267	-0.021546	-0.064639	9.765301	0.047564	0.088998	-0.036505
+6.704271	-0.011970	-0.040699	9.772483	0.046231	0.089665	-0.040769
+6.705270	-0.026334	-0.016758	9.817970	0.045565	0.090331	-0.038637
+6.706271	-0.004788	-0.052669	9.894580	0.047031	0.090464	-0.034907
+6.707270	0.007182	-0.009576	9.849093	0.047031	0.090997	-0.033308
+6.708269	-0.004788	-0.038305	9.853881	0.047031	0.090464	-0.032109
+6.709271	-0.028729	-0.057457	9.796424	0.047164	0.088732	-0.033308
+6.710270	-0.026334	-0.057457	9.803606	0.045032	0.085668	-0.034507
+6.711270	-0.014364	0.007182	9.841911	0.045299	0.084868	-0.037038
+6.712270	-0.019152	-0.045487	9.815576	0.046498	0.084469	-0.038770
+6.713246	-0.019152	-0.021546	9.808394	0.044233	0.083936	-0.034640
+6.714249	0.055063	-0.026334	9.789242	0.046631	0.087933	-0.036772
+6.715278	0.043093	-0.026334	9.841911	0.050361	0.087266	-0.039436
+6.716265	0.007182	0.014364	9.870639	0.051161	0.085534	-0.034640
+6.717271	-0.016758	-0.014364	9.813182	0.048896	0.085934	-0.035040
+6.718267	-0.038305	-0.014364	9.789242	0.047430	0.088332	-0.036372
+6.719242	-0.081397	0.021546	9.822758	0.045698	0.089665	-0.039303
+6.720233	0.016758	0.031123	9.918520	0.046897	0.088998	-0.033708
+6.721272	0.023940	-0.004788	9.880215	0.046231	0.089132	-0.032642
+6.722273	-0.055063	-0.057457	9.767695	0.048763	0.087933	-0.035173
+6.723223	-0.050275	-0.033517	9.726997	0.048496	0.088998	-0.036106
+6.724244	-0.002394	0.011970	9.794030	0.047031	0.089798	-0.036639
+6.725271	0.002394	-0.040699	9.889792	0.046631	0.088466	-0.034107
+6.726271	-0.007182	-0.007182	9.896974	0.048363	0.087666	-0.033041
+6.727270	0.000000	0.011970	9.837123	0.049029	0.087133	-0.036106
+6.728190	-0.014364	-0.002394	9.798818	0.049296	0.087266	-0.036372
+6.729215	-0.028729	0.016758	9.729391	0.044100	0.088199	-0.037438
+6.730273	-0.014364	-0.026334	9.746149	0.043700	0.086600	-0.038504
+6.731270	-0.014364	0.009576	9.734179	0.045165	0.087400	-0.039703
+6.732269	0.002394	-0.007182	9.755725	0.047031	0.090198	-0.038371
+6.733225	0.011970	-0.028729	9.841911	0.044233	0.088732	-0.037438
+6.734262	0.014364	-0.062245	9.887397	0.045565	0.084602	-0.034107
+6.735270	-0.014364	-0.026334	9.801212	0.046764	0.083936	-0.035306
+6.736269	-0.014364	-0.033517	9.870639	0.047031	0.087000	-0.036639
+6.737271	0.007182	-0.014364	9.873033	0.046631	0.090730	-0.035972
+6.738272	-0.002394	-0.004788	9.806000	0.046498	0.088199	-0.035972
+6.739208	-0.002394	-0.031123	9.770089	0.046231	0.085401	-0.033841
+6.740193	0.021546	-0.028729	9.786848	0.046364	0.087000	-0.031176
+6.741193	0.023940	-0.016758	9.741361	0.046764	0.088199	-0.034240
+6.742271	0.033517	-0.040699	9.674328	0.045565	0.087266	-0.033974
+6.743265	0.047881	-0.035911	9.681510	0.046231	0.086867	-0.032642
+6.744257	0.059851	-0.062245	9.825152	0.047297	0.087799	-0.034240
+6.745265	0.009576	-0.043093	9.794030	0.045832	0.087933	-0.035839
+6.746270	-0.011970	0.043093	9.825152	0.046098	0.086867	-0.032109
+6.747271	0.023940	0.007182	9.767695	0.046098	0.085002	-0.036239
+6.748269	0.011970	-0.007182	9.758119	0.045698	0.086201	-0.038637
+6.749214	-0.011970	-0.004788	9.870639	0.044766	0.086734	-0.036639
+6.750272	-0.002394	0.023940	9.858669	0.044233	0.085401	-0.037305
+6.751271	-0.009576	0.002394	9.923308	0.047697	0.086867	-0.038904
+6.752208	-0.016758	0.021546	9.920914	0.047697	0.089265	-0.036106
+6.753194	0.021546	-0.023940	9.851487	0.047697	0.088865	-0.034507
+6.754193	0.016758	-0.052669	9.784454	0.048096	0.087666	-0.034907
+6.755187	0.033517	-0.014364	9.736573	0.047697	0.090064	-0.035573
+6.756218	0.045487	-0.004788	9.789242	0.044899	0.089798	-0.035040
+6.757269	0.007182	-0.002394	9.817970	0.044100	0.086867	-0.034507
+6.758197	-0.011970	0.002394	9.734179	0.044366	0.086067	-0.035306
+6.759265	0.021546	-0.011970	9.796424	0.045698	0.086600	-0.037838
+6.760269	0.004788	-0.023940	9.767695	0.047297	0.087533	-0.039436
+6.761270	0.002394	-0.009576	9.825152	0.047830	0.089398	-0.039969
+6.762270	0.028729	0.004788	9.791636	0.047164	0.088998	-0.034773
+6.763268	-0.019152	-0.052669	9.794030	0.047830	0.087533	-0.034640
+6.764269	-0.014364	-0.055063	9.853881	0.048363	0.086734	-0.035440
+6.765273	-0.031123	-0.016758	9.858669	0.048096	0.090464	-0.035706
+6.766225	-0.033517	0.026334	9.801212	0.047031	0.089931	-0.036372
+6.767266	0.045487	-0.007182	9.782060	0.047830	0.087133	-0.035306
+6.768244	0.000000	-0.055063	9.873033	0.049029	0.087000	-0.034907
+6.769239	-0.035911	-0.002394	9.882609	0.048763	0.088332	-0.035706
+6.770266	0.000000	0.014364	9.803606	0.049162	0.087400	-0.040103
+6.771270	0.028729	-0.031123	9.789242	0.046764	0.086734	-0.038371
+6.772268	0.045487	-0.033517	9.786848	0.045565	0.088998	-0.038504
+6.773269	0.004788	0.007182	9.837123	0.047031	0.087933	-0.036505
+6.774270	-0.023940	0.090974	9.755725	0.046631	0.087000	-0.037571
+6.775253	-0.007182	-0.019152	9.798818	0.048096	0.087933	-0.036505
+6.776282	-0.009576	-0.011970	9.784454	0.048096	0.089665	-0.035040
+6.777271	-0.014364	0.009576	9.710238	0.047697	0.089931	-0.037971
+6.778271	-0.004788	0.011970	9.717420	0.047430	0.091263	-0.036106
+6.779210	0.014364	0.050275	9.784454	0.046364	0.090064	-0.035173
+6.780268	-0.059851	-0.007182	9.772483	0.045299	0.084868	-0.035839
+6.781269	-0.009576	-0.059851	9.827546	0.045432	0.083270	-0.035173
+6.782269	-0.035911	0.002394	9.856275	0.047697	0.087533	-0.035839
+6.783268	0.009576	0.000000	9.837123	0.047697	0.088599	-0.035173
+6.784205	0.033517	0.043093	9.760513	0.049296	0.087666	-0.034107
+6.785209	0.014364	0.000000	9.743755	0.051694	0.088332	-0.034640
+6.786230	-0.035911	-0.055063	9.741361	0.048629	0.089931	-0.034240
+6.787269	0.035911	0.043093	9.743755	0.046498	0.088865	-0.036239
+6.788257	0.055063	-0.002394	9.782060	0.046498	0.088066	-0.036106
+6.789254	0.055063	0.016758	9.832334	0.045565	0.087266	-0.035306
+6.790270	0.035911	-0.009576	9.841911	0.046364	0.087266	-0.034773
+6.791268	-0.014364	-0.071821	9.796424	0.048230	0.086334	-0.036905
+6.792210	0.016758	-0.011970	9.794030	0.049296	0.087799	-0.037838
+6.793269	0.014364	0.009576	9.767695	0.046098	0.085534	-0.036106
+6.794269	0.000000	-0.028729	9.741361	0.045432	0.085934	-0.033974
+6.795239	-0.021546	-0.040699	9.734179	0.045032	0.086334	-0.034640
+6.796262	0.014364	-0.026334	9.829940	0.047031	0.087133	-0.035306
+6.797166	0.014364	-0.043093	9.856275	0.049429	0.086467	-0.037838
+6.798173	0.050275	0.002394	9.832334	0.049162	0.086201	-0.037305
+6.799171	0.028729	0.011970	9.901762	0.048629	0.089798	-0.036905
+6.800183	0.002394	0.002394	9.815576	0.048230	0.088998	-0.038770
+6.801186	0.023940	0.002394	9.806000	0.046631	0.086334	-0.035440
+6.802186	0.000000	-0.009576	9.784454	0.045965	0.084469	-0.036639
+6.803187	-0.009576	-0.033517	9.777271	0.045032	0.085135	-0.036639
+6.804192	0.011970	-0.014364	9.801212	0.046098	0.087266	-0.033308
+6.805192	-0.009576	0.038305	9.873033	0.046631	0.087266	-0.036505
+6.806193	0.021546	-0.011970	9.841911	0.045698	0.088865	-0.038770
+6.807187	0.069427	-0.031123	9.786848	0.049029	0.088199	-0.037438
+6.808189	0.002394	-0.004788	9.794030	0.049029	0.088865	-0.037838
+6.809193	-0.002394	-0.064639	9.801212	0.049562	0.088066	-0.035706
+6.810193	-0.021546	-0.026334	9.774877	0.049429	0.088066	-0.038237
+6.811188	0.014364	-0.021546	9.772483	0.048363	0.087933	-0.035040
+6.812192	0.026334	-0.059851	9.750937	0.047164	0.085934	-0.035972
+6.813193	-0.004788	-0.033517	9.748543	0.048629	0.087133	-0.035573
+6.814194	0.045487	-0.038305	9.789242	0.047697	0.090198	-0.037838
+6.815192	-0.026334	0.043093	9.849093	0.048230	0.088865	-0.037438
+6.816192	-0.047881	0.026334	9.803606	0.049695	0.086467	-0.037438
+6.817192	-0.043093	-0.047881	9.705450	0.047430	0.086201	-0.039570
+6.818195	-0.033517	-0.059851	9.772483	0.047430	0.086467	-0.037971
+6.819192	-0.016758	-0.031123	9.791636	0.048629	0.087666	-0.035972
+6.820187	-0.023940	-0.023940	9.803606	0.048896	0.088466	-0.036372
+6.821186	0.031123	0.016758	9.808394	0.045698	0.088199	-0.035706
+6.822192	0.007182	-0.014364	9.832334	0.043567	0.088066	-0.036239
+6.823190	0.033517	-0.052669	9.810788	0.045965	0.089132	-0.040236
+6.824191	0.004788	-0.021546	9.825152	0.049296	0.087266	-0.040236
+6.825179	-0.031123	0.021546	9.753331	0.051560	0.084735	-0.038104
+6.826192	-0.038305	-0.043093	9.846699	0.048763	0.085934	-0.037038
+6.827191	-0.002394	0.002394	9.853881	0.047564	0.088199	-0.033708
+6.828187	0.011970	0.000000	9.705450	0.048096	0.088998	-0.037838
+6.829168	0.004788	-0.016758	9.772483	0.045965	0.088599	-0.041568
+6.830189	0.023940	-0.038305	9.834729	0.044366	0.087400	-0.034907
+6.831192	-0.002394	-0.043093	9.782060	0.046897	0.089531	-0.033841
+6.832186	-0.009576	-0.055063	9.755725	0.045165	0.091930	-0.033841
+6.833192	-0.023940	-0.043093	9.695874	0.045965	0.091796	-0.033974
+6.834188	0.050275	-0.033517	9.750937	0.048230	0.088466	-0.034374
+6.835192	0.038305	-0.019152	9.724603	0.046897	0.085268	-0.036505
+6.836192	0.004788	-0.033517	9.755725	0.046631	0.084469	-0.032375
+6.837191	0.023940	-0.016758	9.839517	0.047297	0.084069	-0.034107
+6.838187	0.038305	0.045487	9.820364	0.046231	0.088466	-0.034240
+6.839192	0.016758	-0.007182	9.822758	0.046098	0.089265	-0.035173
+6.840192	-0.031123	-0.021546	9.794030	0.046498	0.089265	-0.038637
+6.841196	-0.019152	0.035911	9.779666	0.045432	0.088599	-0.036905
+6.842191	-0.014364	0.033517	9.772483	0.045032	0.088066	-0.035440
+6.843191	-0.086186	0.026334	9.772483	0.049162	0.087266	-0.037038
+6.844191	0.019152	-0.004788	9.810788	0.047430	0.087266	-0.035040
+6.845186	0.000000	-0.021546	9.784454	0.044233	0.085401	-0.035573
+6.846192	-0.023940	0.071821	9.779666	0.044233	0.085401	-0.039170
+6.847186	0.002394	0.038305	9.729391	0.046631	0.087799	-0.037172
+6.848181	-0.007182	-0.007182	9.738967	0.048896	0.088066	-0.037305
+6.849192	0.014364	-0.014364	9.834729	0.048629	0.087799	-0.037438
+6.850188	0.050275	0.035911	9.803606	0.047830	0.089931	-0.037571
+6.851263	0.021546	0.019152	9.846699	0.048230	0.088466	-0.036239
+6.852239	0.035911	0.055063	9.748543	0.047697	0.088199	-0.039303
+6.853217	0.019152	-0.002394	9.753331	0.046631	0.088998	-0.038237
+6.854264	-0.014364	-0.014364	9.777271	0.045832	0.089132	-0.036905
+6.855211	0.028729	-0.038305	9.822758	0.045165	0.088599	-0.035173
+6.856203	0.038305	0.007182	9.829940	0.047164	0.088599	-0.035040
+6.857269	0.002394	0.026334	9.817970	0.048896	0.086867	-0.034640
+6.858271	0.002394	-0.031123	9.794030	0.047164	0.086734	-0.031975
+6.859270	0.000000	-0.062245	9.772483	0.044499	0.087133	-0.031975
+6.860264	0.009576	-0.016758	9.794030	0.045165	0.087933	-0.036106
+6.861269	-0.064639	-0.009576	9.820364	0.049562	0.090597	-0.037305
+6.862268	0.019152	-0.016758	9.820364	0.048363	0.090064	-0.039570
+6.863250	0.021546	-0.043093	9.734179	0.048763	0.090198	-0.038904
+6.864241	0.004788	-0.045487	9.786848	0.048363	0.089931	-0.035972
+6.865269	-0.026334	-0.028729	9.794030	0.047031	0.089665	-0.036372
+6.866270	0.055063	0.007182	9.753331	0.047031	0.090198	-0.036239
+6.867269	0.011970	-0.016758	9.693480	0.045565	0.089531	-0.035440
+6.868268	0.031123	-0.021546	9.777271	0.045965	0.087266	-0.036639
+6.869250	-0.011970	0.016758	9.767695	0.045432	0.088466	-0.037838
+6.870267	-0.023940	-0.011970	9.806000	0.046098	0.089132	-0.040769
+6.871270	-0.055063	0.007182	9.827546	0.046631	0.085668	-0.038504
+6.872267	0.050275	0.014364	9.853881	0.046098	0.086201	-0.035573
+6.873228	0.033517	-0.093368	9.849093	0.045965	0.086334	-0.037438
+6.874240	0.011970	-0.045487	9.801212	0.048096	0.086334	-0.033041
+6.875270	0.040699	-0.023940	9.829940	0.048096	0.086334	-0.033175
+6.876269	0.076609	-0.031123	9.789242	0.048096	0.084069	-0.036639
+6.877263	-0.023940	-0.023940	9.772483	0.047031	0.085934	-0.036505
+6.878249	-0.028729	-0.035911	9.777271	0.046098	0.090730	-0.037571
+6.879177	-0.014364	-0.023940	9.798818	0.045032	0.092329	-0.036106
+6.880260	-0.028729	-0.011970	9.832334	0.044233	0.090597	-0.033175
+6.881270	-0.038305	-0.026334	9.892186	0.043966	0.090198	-0.032508
+6.882265	0.033517	-0.011970	9.825152	0.044766	0.087666	-0.033974
+6.883238	0.021546	-0.038305	9.798818	0.046764	0.086600	-0.038504
+6.884219	0.019152	0.009576	9.798818	0.046098	0.088998	-0.040636
+6.885221	0.000000	-0.019152	9.815576	0.047564	0.090864	-0.036905
+6.886271	0.011970	-0.014364	9.738967	0.045965	0.089931	-0.037038
+6.887268	-0.004788	-0.004788	9.825152	0.044233	0.089132	-0.038637
+6.888221	0.052669	-0.026334	9.849093	0.044899	0.088732	-0.038504
+6.889269	0.019152	0.007182	9.822758	0.047164	0.087400	-0.038770
+6.890269	0.033517	0.016758	9.770089	0.047297	0.086467	-0.038237
+6.891267	-0.023940	0.002394	9.743755	0.046631	0.086734	-0.035972
+6.892270	-0.014364	-0.064639	9.810788	0.046098	0.086867	-0.034640
+6.893240	0.031123	-0.050275	9.817970	0.046231	0.089398	-0.035440
+6.894221	-0.004788	-0.031123	9.813182	0.045299	0.087533	-0.032642
+6.895266	-0.002394	-0.026334	9.782060	0.043966	0.086467	-0.034374
+6.896267	0.014364	-0.002394	9.729391	0.046098	0.085801	-0.035839
+6.897212	0.033517	0.000000	9.738967	0.048096	0.086600	-0.037438
+6.898255	0.004788	-0.033517	9.767695	0.047830	0.086734	-0.038637
+6.899247	0.009576	-0.009576	9.853881	0.045698	0.086867	-0.039303
+6.900269	0.040699	0.002394	9.825152	0.044366	0.085934	-0.038504
+6.901270	-0.019152	0.052669	9.726997	0.045832	0.086600	-0.035306
+6.902250	0.021546	0.035911	9.753331	0.048896	0.087799	-0.034240
+6.903269	-0.004788	0.074215	9.729391	0.046897	0.087400	-0.037704
+6.904240	0.033517	0.031123	9.736573	0.045032	0.086734	-0.042634
+6.905253	0.000000	-0.016758	9.832334	0.045432	0.086067	-0.040236
+6.906269	0.023940	0.019152	9.837123	0.047963	0.085401	-0.036106
+6.907269	0.050275	-0.009576	9.801212	0.049695	0.089398	-0.033708
+6.908225	0.038305	-0.019152	9.729391	0.046897	0.087266	-0.036505
+6.909268	-0.023940	-0.011970	9.820364	0.044233	0.085801	-0.039303
+6.910270	-0.028729	-0.016758	9.825152	0.044632	0.083669	-0.038371
+6.911268	0.007182	0.033517	9.875427	0.045165	0.083270	-0.034107
+6.912264	0.038305	0.050275	9.815576	0.043966	0.086467	-0.033308
+6.913244	0.050275	-0.019152	9.813182	0.045832	0.089931	-0.035040
+6.914212	0.021546	-0.007182	9.815576	0.046764	0.087266	-0.036772
+6.915252	-0.028729	0.004788	9.743755	0.047164	0.083802	-0.038104
+6.916263	0.004788	-0.102944	9.808394	0.047430	0.085934	-0.035306
+6.917207	-0.019152	-0.011970	9.849093	0.047297	0.088199	-0.035706
+6.918187	-0.011970	-0.007182	9.810788	0.046498	0.086600	-0.037038
+6.919193	0.023940	-0.009576	9.865851	0.045698	0.085002	-0.039170
+6.920221	0.043093	-0.004788	9.846699	0.044766	0.086467	-0.036505
+6.921270	0.023940	-0.043093	9.825152	0.045032	0.087400	-0.034773
+6.922269	0.038305	-0.016758	9.829940	0.045698	0.088865	-0.038104
+6.923269	-0.021546	-0.016758	9.755725	0.047564	0.089398	-0.040636
+6.924270	-0.031123	0.031123	9.760513	0.047830	0.088998	-0.038371
+6.925260	0.040699	-0.023940	9.772483	0.047697	0.088066	-0.036106
+6.926257	0.033517	-0.047881	9.750937	0.047963	0.086067	-0.038237
+6.927206	-0.011970	-0.038305	9.738967	0.046631	0.086734	-0.037038
+6.928242	-0.040699	0.021546	9.813182	0.045965	0.089531	-0.039037
+6.929188	-0.021546	0.059851	9.770089	0.045698	0.088599	-0.036372
+6.930253	-0.057457	0.004788	9.765301	0.046764	0.088332	-0.037971
+6.931269	-0.016758	-0.004788	9.772483	0.045965	0.088998	-0.040902
+6.932269	0.019152	-0.026334	9.777271	0.047164	0.086867	-0.037971
+6.933241	0.047881	-0.026334	9.875427	0.048896	0.086067	-0.037704
+6.934225	-0.069427	0.004788	9.894580	0.050095	0.085668	-0.035972
+6.935208	-0.023940	0.057457	9.774877	0.047430	0.084602	-0.036639
+6.936229	-0.055063	0.016758	9.770089	0.044233	0.085268	-0.039570
+6.937240	-0.011970	-0.014364	9.784454	0.045832	0.089132	-0.037172
+6.938270	-0.014364	0.011970	9.746149	0.045832	0.089798	-0.037971
+6.939269	0.014364	-0.019152	9.770089	0.047031	0.087133	-0.036905
+6.940269	0.000000	0.021546	9.707844	0.047697	0.087666	-0.036106
+6.941267	0.007182	0.000000	9.782060	0.049162	0.087400	-0.034640
+6.942268	0.040699	-0.016758	9.784454	0.049429	0.087666	-0.032109
+6.943268	0.014364	-0.002394	9.772483	0.049162	0.088066	-0.036639
+6.944230	-0.026334	0.021546	9.772483	0.045832	0.088332	-0.034640
+6.945224	0.016758	0.023940	9.813182	0.045032	0.091796	-0.035573
+6.946251	0.040699	-0.040699	9.784454	0.045299	0.091130	-0.039969
+6.947266	0.047881	-0.019152	9.827546	0.046231	0.088865	-0.038104
+6.948268	0.016758	0.004788	9.762907	0.046364	0.087133	-0.038637
+6.949214	-0.028729	-0.026334	9.817970	0.045965	0.087799	-0.034640
+6.950269	-0.057457	0.011970	9.782060	0.044100	0.088998	-0.034507
+6.951216	-0.026334	0.009576	9.738967	0.046498	0.090730	-0.034640
+6.952266	-0.016758	-0.019152	9.822758	0.047297	0.091663	-0.037038
+6.953268	-0.031123	0.002394	9.762907	0.046764	0.092462	-0.038104
+6.954267	-0.023940	0.035911	9.798818	0.045432	0.091796	-0.035040
+6.955237	-0.009576	0.007182	9.844305	0.045965	0.089798	-0.034640
+6.956230	0.028729	0.009576	9.825152	0.047297	0.088732	-0.035573
+6.957270	0.026334	0.031123	9.810788	0.045965	0.089132	-0.034640
+6.958269	0.014364	-0.019152	9.777271	0.044899	0.087933	-0.036639
+6.959253	0.045487	-0.033517	9.784454	0.047164	0.086867	-0.034640
+6.960235	-0.009576	-0.038305	9.796424	0.047697	0.088332	-0.035972
+6.961267	-0.026334	0.016758	9.803606	0.047697	0.086467	-0.036106
+6.962271	0.009576	0.040699	9.806000	0.045832	0.086867	-0.036239
+6.963268	0.057457	0.007182	9.729391	0.044233	0.089265	-0.035440
+6.964268	-0.019152	-0.035911	9.734179	0.046498	0.088998	-0.036372
+6.965256	-0.011970	0.016758	9.827546	0.048763	0.087666	-0.035839
+6.966266	0.021546	-0.019152	9.877821	0.049029	0.088998	-0.035706
+6.967267	0.028729	0.043093	9.798818	0.047830	0.088865	-0.035040
+6.968249	0.026334	-0.033517	9.894580	0.047830	0.087133	-0.037038
+6.969208	0.028729	-0.016758	9.841911	0.047430	0.087666	-0.034507
+6.970232	0.000000	-0.014364	9.906550	0.047297	0.089531	-0.035706
+6.971235	-0.019152	-0.007182	9.822758	0.045432	0.088066	-0.038504
+6.972229	-0.002394	-0.016758	9.849093	0.046897	0.086067	-0.036239
+6.973267	0.083792	-0.016758	9.861063	0.048496	0.087133	-0.035040
+6.974268	0.059851	0.052669	9.798818	0.050095	0.086201	-0.036505
+6.975235	0.011970	-0.023940	9.784454	0.048096	0.087266	-0.038904
+6.976230	-0.040699	-0.019152	9.849093	0.047830	0.089265	-0.036372
+6.977270	-0.035911	-0.033517	9.789242	0.049429	0.089798	-0.035173
+6.978240	0.043093	-0.040699	9.786848	0.046231	0.088466	-0.036639
+6.979191	0.043093	-0.038305	9.856275	0.043966	0.087799	-0.037038
+6.980200	0.028729	0.002394	9.832334	0.045965	0.089398	-0.038371
+6.981267	0.000000	-0.002394	9.693480	0.046364	0.087400	-0.035173
+6.982262	0.007182	-0.002394	9.743755	0.046764	0.087400	-0.034240
+6.983266	0.009576	-0.002394	9.801212	0.045432	0.088466	-0.036639
+6.984209	-0.074215	0.026334	9.808394	0.045965	0.087400	-0.036772
+6.985268	-0.026334	0.059851	9.784454	0.047031	0.085401	-0.037438
+6.986254	0.031123	0.014364	9.729391	0.049029	0.084069	-0.036772
+6.987208	0.021546	0.007182	9.746149	0.049562	0.087400	-0.036639
+6.988191	0.016758	-0.067033	9.750937	0.046764	0.089531	-0.035040
+6.989265	0.035911	-0.050275	9.715026	0.045432	0.088199	-0.034107
+6.990261	-0.023940	-0.050275	9.779666	0.044499	0.087133	-0.033574
+6.991265	-0.067033	-0.031123	9.810788	0.048496	0.088066	-0.035972
+6.992266	-0.033517	-0.057457	9.849093	0.048629	0.088599	-0.035706
+6.993268	-0.016758	0.028729	9.810788	0.048230	0.088865	-0.038504
+6.994267	0.004788	0.016758	9.798818	0.047564	0.087666	-0.034374
+6.995265	0.057457	0.035911	9.770089	0.046897	0.085934	-0.037971
+6.996255	-0.004788	0.026334	9.772483	0.046098	0.087000	-0.037838
+6.997258	0.011970	0.002394	9.738967	0.044233	0.086467	-0.036639
+6.998253	-0.038305	-0.004788	9.801212	0.044499	0.087533	-0.034507
+6.999210	-0.040699	-0.019152	9.870639	0.043833	0.089798	-0.033574
+7.000266	0.031123	-0.009576	9.801212	0.043966	0.085268	-0.035306
+7.001265	0.014364	-0.045487	9.815576	0.044766	0.084735	-0.037704
+7.002209	0.007182	-0.031123	9.796424	0.047697	0.085534	-0.037038
+7.003266	0.016758	-0.016758	9.846699	0.049562	0.086334	-0.040369
+7.004267	0.038305	-0.004788	9.822758	0.048629	0.086201	-0.038504
+7.005267	0.033517	0.009576	9.726997	0.047697	0.088332	-0.035706
+7.006257	-0.011970	0.026334	9.695874	0.047164	0.090464	-0.035173
+7.007259	-0.009576	0.002394	9.784454	0.047031	0.089931	-0.037038
+7.008221	0.021546	-0.033517	9.743755	0.045032	0.088998	-0.038371
+7.009266	0.019152	-0.026334	9.748543	0.048096	0.087799	-0.037038
+7.010266	0.007182	0.007182	9.758119	0.049296	0.087799	-0.035972
+7.011266	0.026334	-0.045487	9.829940	0.047297	0.088599	-0.034374
+7.012264	0.076609	-0.026334	9.861063	0.048629	0.087000	-0.033974
+7.013265	0.040699	0.016758	9.858669	0.048763	0.088998	-0.035706
+7.014265	0.011970	-0.038305	9.865851	0.047297	0.088865	-0.037704
+7.015264	-0.045487	-0.045487	9.834729	0.046364	0.087666	-0.037038
+7.016239	0.000000	-0.009576	9.817970	0.044499	0.087933	-0.035972
+7.017251	0.031123	0.043093	9.829940	0.047297	0.088732	-0.040369
+7.018266	-0.004788	-0.021546	9.806000	0.048629	0.088466	-0.037305
+7.019254	-0.021546	-0.009576	9.731785	0.049695	0.088066	-0.036106
+7.020233	0.031123	0.028729	9.791636	0.048096	0.084868	-0.035972
+7.021266	0.011970	-0.031123	9.822758	0.048496	0.086067	-0.035173
+7.022268	-0.011970	-0.016758	9.820364	0.049162	0.086734	-0.037704
+7.023266	-0.011970	-0.033517	9.813182	0.046098	0.088732	-0.035440
+7.024267	0.011970	-0.026334	9.715026	0.047164	0.089398	-0.034773
+7.025267	0.009576	-0.043093	9.786848	0.048763	0.090331	-0.037305
+7.026211	0.026334	-0.016758	9.837123	0.049562	0.088199	-0.035706
+7.027269	0.033517	-0.035911	9.839517	0.048096	0.088732	-0.035573
+7.028235	0.023940	-0.052669	9.863457	0.048230	0.087933	-0.038504
+7.029202	0.038305	-0.083792	9.841911	0.048363	0.085801	-0.036772
+7.030153	0.009576	-0.038305	9.760513	0.048363	0.086600	-0.036772
+7.031175	-0.021546	-0.007182	9.774877	0.048363	0.089132	-0.037838
+7.032224	0.004788	-0.031123	9.880215	0.047830	0.089398	-0.036772
+7.033236	-0.014364	0.028729	9.873033	0.046498	0.087400	-0.038371
+7.034223	0.000000	0.021546	9.817970	0.045965	0.088199	-0.039037
+7.035266	0.033517	-0.026334	9.738967	0.046764	0.087000	-0.037438
+7.036266	0.040699	0.007182	9.758119	0.048363	0.084602	-0.039703
+7.037232	-0.023940	-0.043093	9.851487	0.047297	0.086734	-0.038504
+7.038226	-0.052669	-0.009576	9.834729	0.047297	0.089665	-0.035706
+7.039216	0.014364	-0.016758	9.815576	0.046231	0.088599	-0.035573
+7.040216	-0.021546	-0.004788	9.798818	0.047164	0.088998	-0.035706
+7.041218	0.047881	0.021546	9.734179	0.048629	0.090198	-0.036505
+7.042194	0.052669	0.043093	9.791636	0.048496	0.090064	-0.036639
+7.043204	0.019152	0.028729	9.760513	0.045299	0.085401	-0.037571
+7.044267	0.033517	0.035911	9.767695	0.046897	0.086067	-0.034240
+7.045265	0.019152	0.031123	9.822758	0.047564	0.088466	-0.035839
+7.046261	0.011970	0.004788	9.791636	0.046498	0.088066	-0.036372
+7.047265	0.033517	-0.011970	9.829940	0.046764	0.091130	-0.033441
+7.048213	0.026334	0.004788	9.868245	0.046631	0.088466	-0.035173
+7.049204	-0.004788	-0.011970	9.849093	0.047164	0.088466	-0.037305
+7.050174	-0.023940	0.004788	9.731785	0.047031	0.089398	-0.034240
+7.051234	-0.021546	0.040699	9.774877	0.045832	0.087666	-0.031709
+7.052233	-0.014364	0.016758	9.803606	0.044499	0.088066	-0.033175
+7.053233	0.021546	0.000000	9.798818	0.044233	0.088998	-0.033974
+7.054235	0.031123	0.007182	9.873033	0.044366	0.089665	-0.037038
+7.055234	0.002394	0.009576	9.774877	0.043433	0.088599	-0.037704
+7.056233	-0.050275	0.033517	9.734179	0.047963	0.085534	-0.036505
+7.057235	0.031123	0.074215	9.784454	0.048629	0.087933	-0.036772
+7.058234	0.011970	0.009576	9.738967	0.045832	0.089398	-0.034773
+7.059191	0.055063	0.026334	9.750937	0.045832	0.087933	-0.034773
+7.060232	-0.031123	0.021546	9.772483	0.044499	0.088599	-0.035173
+7.061235	-0.007182	-0.004788	9.813182	0.046231	0.087133	-0.036505
+7.062236	0.023940	-0.004788	9.925702	0.047164	0.087400	-0.035040
+7.063229	0.000000	-0.009576	9.813182	0.048896	0.085401	-0.035440
+7.064261	-0.011970	-0.002394	9.844305	0.046897	0.086201	-0.036239
+7.065266	-0.026334	0.007182	9.827546	0.046364	0.087799	-0.036639
+7.066268	0.002394	0.000000	9.796424	0.045832	0.089132	-0.039969
+7.067266	-0.021546	-0.026334	9.825152	0.046764	0.086867	-0.040902
+7.068196	0.000000	-0.033517	9.801212	0.046498	0.085801	-0.039303
+7.069233	-0.026334	-0.002394	9.806000	0.047963	0.086867	-0.038637
+7.070182	0.016758	-0.014364	9.858669	0.049162	0.087666	-0.036239
+7.071287	0.026334	-0.026334	9.810788	0.047830	0.087799	-0.032109
+7.072265	0.074215	-0.069427	9.820364	0.046364	0.088066	-0.035706
+7.073262	0.057457	-0.019152	9.772483	0.044366	0.088466	-0.039836
+7.074268	0.011970	-0.052669	9.844305	0.046897	0.089265	-0.038237
+7.075266	0.031123	-0.035911	9.779666	0.050761	0.088199	-0.036106
+7.076259	0.002394	0.009576	9.794030	0.049695	0.084735	-0.037438
+7.077202	-0.045487	0.011970	9.846699	0.046364	0.086334	-0.035573
+7.078224	-0.016758	0.007182	9.825152	0.045032	0.088998	-0.034507
+7.079247	0.007182	0.009576	9.798818	0.046231	0.087266	-0.033841
+7.080238	0.088580	0.002394	9.767695	0.048230	0.087400	-0.036372
+7.081270	0.086186	-0.043093	9.817970	0.047297	0.087266	-0.038637
+7.082265	0.057457	-0.019152	9.880215	0.047564	0.087400	-0.036905
+7.083263	0.076609	-0.019152	9.746149	0.047297	0.088865	-0.035573
+7.084203	0.040699	0.000000	9.782060	0.046098	0.088865	-0.035839
+7.085198	0.059851	-0.016758	9.794030	0.046098	0.088066	-0.032908
+7.086262	0.050275	0.004788	9.738967	0.046498	0.086867	-0.033175
+7.087236	-0.031123	-0.011970	9.817970	0.046498	0.088332	-0.039037
+7.088249	0.043093	0.014364	9.834729	0.047164	0.088732	-0.039170
+7.089269	0.038305	0.031123	9.770089	0.045965	0.087533	-0.036239
+7.090261	-0.052669	0.009576	9.808394	0.045832	0.086600	-0.033441
+7.091245	-0.045487	-0.007182	9.839517	0.047297	0.087266	-0.036639
+7.092267	0.009576	-0.011970	9.760513	0.047031	0.085934	-0.038770
+7.093264	-0.004788	0.009576	9.731785	0.048763	0.086600	-0.038637
+7.094266	0.026334	-0.028729	9.724603	0.047564	0.088865	-0.034640
+7.095265	0.088580	0.002394	9.772483	0.045565	0.089665	-0.033974
+7.096266	0.026334	-0.028729	9.817970	0.045299	0.089665	-0.036772
+7.097244	0.035911	0.002394	9.829940	0.046231	0.088466	-0.035173
+7.098264	0.052669	0.014364	9.801212	0.046764	0.087666	-0.036106
+7.099251	0.014364	-0.009576	9.887397	0.049695	0.085534	-0.037571
+7.100236	0.038305	-0.026334	9.844305	0.048629	0.087400	-0.036106
+7.101262	0.045487	-0.009576	9.755725	0.045299	0.089265	-0.035573
+7.102267	0.007182	-0.014364	9.734179	0.044766	0.088199	-0.034507
+7.103265	-0.004788	-0.026334	9.789242	0.045565	0.087133	-0.034773
+7.104265	0.031123	-0.011970	9.760513	0.047031	0.086467	-0.037571
+7.105267	-0.004788	-0.009576	9.767695	0.048496	0.086600	-0.039170
+7.106268	-0.011970	0.009576	9.762907	0.048363	0.087799	-0.037704
+7.107264	-0.002394	0.021546	9.863457	0.046764	0.086867	-0.037438
+7.108265	-0.007182	-0.043093	9.913732	0.046098	0.086067	-0.035972
+7.109252	0.021546	0.043093	9.810788	0.046764	0.087533	-0.035173
+7.110239	-0.004788	0.031123	9.825152	0.047430	0.089931	-0.036639
+7.111203	-0.002394	-0.043093	9.856275	0.047164	0.091796	-0.034240
+7.112268	0.014364	-0.098156	9.837123	0.047430	0.089132	-0.034374
+7.113266	0.028729	-0.052669	9.868245	0.048629	0.084602	-0.036106
+7.114265	-0.035911	-0.040699	9.849093	0.049296	0.086467	-0.040103
+7.115265	0.011970	-0.033517	9.827546	0.045698	0.087400	-0.039703
+7.116261	0.000000	-0.016758	9.825152	0.044499	0.085534	-0.035173
+7.117265	0.040699	-0.033517	9.817970	0.045698	0.086334	-0.034107
+7.118228	0.009576	-0.033517	9.774877	0.045432	0.087666	-0.035173
+7.119235	-0.023940	-0.064639	9.753331	0.044632	0.088066	-0.034374
+7.120239	-0.002394	-0.031123	9.750937	0.045965	0.086334	-0.035173
+7.121261	0.000000	-0.026334	9.755725	0.047031	0.084868	-0.034107
+7.122268	0.045487	0.016758	9.863457	0.045965	0.085135	-0.035306
+7.123266	0.055063	-0.016758	9.873033	0.045965	0.085534	-0.040502
+7.124264	0.064639	-0.045487	9.779666	0.047430	0.087000	-0.039303
+7.125267	-0.007182	-0.040699	9.825152	0.048763	0.087133	-0.035972
+7.126266	-0.035911	-0.023940	9.873033	0.048496	0.087533	-0.037971
+7.127265	-0.019152	-0.031123	9.803606	0.045832	0.088732	-0.037971
+7.128265	0.059851	-0.026334	9.657569	0.045832	0.089531	-0.035839
+7.129222	0.090974	-0.014364	9.784454	0.047297	0.088066	-0.033974
+7.130262	0.035911	0.026334	9.858669	0.046364	0.086334	-0.033974
+7.131265	0.014364	0.002394	9.832334	0.043700	0.087799	-0.032642
+7.132265	0.033517	-0.009576	9.794030	0.043034	0.088998	-0.034240
+7.133260	-0.004788	-0.016758	9.832334	0.047164	0.088865	-0.033574
+7.134252	-0.014364	-0.069427	9.837123	0.048096	0.088998	-0.036505
+7.135240	-0.023940	-0.074215	9.813182	0.047430	0.086334	-0.036772
+7.136228	0.011970	-0.038305	9.777271	0.047430	0.087799	-0.037838
+7.137234	0.007182	0.035911	9.750937	0.043966	0.088599	-0.039037
+7.138233	0.009576	0.011970	9.743755	0.043700	0.087400	-0.036639
+7.139231	-0.011970	0.031123	9.841911	0.043433	0.086201	-0.035706
+7.140231	0.064639	-0.040699	9.779666	0.044632	0.087266	-0.034640
+7.141216	0.004788	-0.007182	9.729391	0.047430	0.088332	-0.034907
+7.142208	-0.021546	0.071821	9.703056	0.047963	0.087799	-0.039436
+7.143200	0.004788	0.059851	9.782060	0.049029	0.086867	-0.042368
+7.144228	0.000000	-0.014364	9.798818	0.049562	0.088466	-0.036772
+7.145198	-0.004788	-0.031123	9.779666	0.048496	0.088998	-0.033441
+7.146201	-0.021546	-0.002394	9.820364	0.045698	0.088732	-0.035040
+7.147199	-0.026334	-0.038305	9.841911	0.044233	0.088599	-0.035839
+7.148218	-0.021546	-0.052669	9.832334	0.043966	0.087799	-0.036239
+7.149259	-0.007182	0.000000	9.849093	0.043567	0.088466	-0.040636
+7.150267	0.014364	0.002394	9.782060	0.045698	0.087533	-0.037305
+7.151259	-0.004788	0.002394	9.798818	0.046897	0.087933	-0.034240
+7.152266	0.011970	0.004788	9.863457	0.049296	0.084602	-0.035972
+7.153259	-0.021546	-0.059851	9.829940	0.050894	0.082470	-0.035306
+7.154269	-0.019152	-0.035911	9.786848	0.050228	0.086867	-0.034507
+7.155237	0.019152	-0.028729	9.755725	0.046364	0.088998	-0.034374
+7.156201	0.000000	-0.011970	9.815576	0.046498	0.090198	-0.030510
+7.157265	0.033517	-0.023940	9.832334	0.047031	0.090064	-0.032642
+7.158267	0.028729	0.009576	9.779666	0.047031	0.087666	-0.036905
+7.159260	-0.014364	-0.011970	9.815576	0.045832	0.084735	-0.038504
+7.160240	-0.004788	0.009576	9.774877	0.045965	0.086867	-0.039570
+7.161240	0.033517	0.035911	9.803606	0.046231	0.087400	-0.038237
+7.162230	0.035911	0.009576	9.789242	0.047564	0.089798	-0.035440
+7.163261	0.014364	-0.035911	9.791636	0.047697	0.089132	-0.032375
+7.164262	0.033517	-0.009576	9.834729	0.047430	0.089531	-0.035040
+7.165261	0.014364	0.002394	9.801212	0.047564	0.090597	-0.035306
+7.166264	0.007182	-0.002394	9.760513	0.048230	0.088199	-0.039836
+7.167264	-0.014364	0.016758	9.798818	0.048096	0.088466	-0.040636
+7.168255	-0.004788	0.011970	9.789242	0.048096	0.087533	-0.037438
+7.169265	0.014364	0.016758	9.825152	0.045698	0.088199	-0.034773
+7.170235	-0.011970	0.026334	9.770089	0.045565	0.087933	-0.033308
+7.171224	-0.004788	-0.023940	9.719814	0.048763	0.087400	-0.037172
+7.172240	-0.009576	-0.021546	9.724603	0.045698	0.087266	-0.038371
+7.173264	-0.026334	-0.002394	9.782060	0.043833	0.087933	-0.036772
+7.174265	0.016758	0.023940	9.779666	0.046098	0.088599	-0.037172
+7.175265	0.031123	0.016758	9.837123	0.046764	0.086734	-0.034640
+7.176264	0.045487	0.016758	9.837123	0.045432	0.087533	-0.035573
+7.177238	0.011970	0.043093	9.770089	0.046498	0.085801	-0.039170
+7.178201	-0.014364	0.007182	9.782060	0.047297	0.087799	-0.041302
+7.179264	-0.019152	0.026334	9.832334	0.043833	0.088599	-0.040636
+7.180234	0.014364	0.021546	9.796424	0.044899	0.088199	-0.037172
+7.181232	-0.016758	0.004788	9.815576	0.046897	0.087400	-0.035839
+7.182238	0.002394	0.045487	9.738967	0.047697	0.086334	-0.037838
+7.183265	-0.011970	0.028729	9.767695	0.049429	0.086201	-0.039836
+7.184235	0.007182	0.055063	9.849093	0.046498	0.086600	-0.038237
+7.185197	-0.031123	0.055063	9.755725	0.045032	0.087000	-0.035306
+7.186264	0.064639	0.028729	9.698268	0.048363	0.088066	-0.037038
+7.187262	0.074215	-0.026334	9.798818	0.049429	0.089531	-0.036239
+7.188198	0.043093	-0.038305	9.798818	0.048230	0.089931	-0.036239
+7.189186	0.019152	-0.059851	9.856275	0.045698	0.090064	-0.039436
+7.190265	-0.007182	-0.033517	9.846699	0.045698	0.085668	-0.036372
+7.191244	-0.019152	0.007182	9.829940	0.047963	0.084469	-0.034907
+7.192223	0.019152	-0.019152	9.815576	0.047430	0.086334	-0.039170
+7.193240	0.023940	-0.045487	9.813182	0.046098	0.089931	-0.036106
+7.194260	0.009576	-0.009576	9.815576	0.047430	0.089931	-0.034640
+7.195264	-0.057457	0.002394	9.779666	0.047697	0.087666	-0.034507
+7.196265	-0.023940	-0.074215	9.806000	0.047963	0.088066	-0.033441
+7.197264	0.033517	-0.026334	9.806000	0.048496	0.088732	-0.037305
+7.198267	0.016758	-0.011970	9.789242	0.048763	0.087666	-0.035839
+7.199265	0.021546	0.009576	9.827546	0.047830	0.084735	-0.032242
+7.200264	0.004788	-0.052669	9.846699	0.046498	0.085934	-0.035040
+7.201175	0.002394	-0.057457	9.724603	0.047031	0.087000	-0.035173
+7.202232	0.031123	0.002394	9.813182	0.047963	0.088998	-0.036372
+7.203258	0.023940	0.045487	9.810788	0.046498	0.088066	-0.038504
+7.204267	0.026334	0.031123	9.722208	0.045165	0.087400	-0.035573
+7.205264	0.035911	0.007182	9.758119	0.044766	0.087666	-0.035306
+7.206265	-0.009576	-0.057457	9.810788	0.044899	0.088066	-0.037305
+7.207263	0.002394	-0.040699	9.806000	0.045565	0.088066	-0.037704
+7.208230	0.043093	-0.043093	9.777271	0.047830	0.086867	-0.035706
+7.209208	0.059851	0.002394	9.815576	0.047963	0.085401	-0.034907
+7.210177	0.035911	-0.047881	9.825152	0.048629	0.085401	-0.034507
+7.211187	-0.007182	-0.023940	9.798818	0.047697	0.088332	-0.038104
+7.212231	0.000000	0.011970	9.832334	0.046498	0.090064	-0.037838
+7.213207	-0.035911	0.016758	9.896974	0.045432	0.091397	-0.037305
+7.214203	-0.009576	0.016758	9.827546	0.044899	0.089132	-0.037038
+7.215265	-0.004788	0.021546	9.777271	0.043167	0.087400	-0.036372
+7.216240	0.016758	0.009576	9.736573	0.045965	0.089398	-0.035440
+7.217213	0.019152	-0.007182	9.760513	0.048629	0.091263	-0.036772
+7.218181	0.028729	-0.007182	9.741361	0.048363	0.090730	-0.036639
+7.219233	0.014364	0.023940	9.841911	0.048230	0.088998	-0.033708
+7.220231	-0.045487	0.002394	9.832334	0.047164	0.088732	-0.036106
+7.221265	-0.021546	-0.016758	9.796424	0.045432	0.088599	-0.037704
+7.222267	-0.004788	0.011970	9.760513	0.045565	0.088599	-0.036106
+7.223260	-0.011970	-0.002394	9.920914	0.047164	0.088599	-0.037971
+7.224204	-0.043093	-0.047881	9.908944	0.047564	0.089798	-0.038637
+7.225216	-0.033517	-0.035911	9.846699	0.048230	0.089398	-0.039170
+7.226236	-0.016758	-0.014364	9.810788	0.047564	0.089931	-0.037838
+7.227230	-0.023940	-0.011970	9.837123	0.045698	0.088599	-0.035306
+7.228237	0.028729	-0.016758	9.803606	0.047430	0.085934	-0.035440
+7.229263	0.050275	-0.011970	9.753331	0.048629	0.085401	-0.036372
+7.230217	0.031123	-0.031123	9.863457	0.047164	0.087133	-0.036106
+7.231263	0.007182	-0.033517	9.806000	0.045965	0.089132	-0.034507
+7.232264	-0.038305	-0.014364	9.784454	0.045832	0.088066	-0.035306
+7.233240	0.016758	-0.009576	9.825152	0.048363	0.086734	-0.037838
+7.234211	0.050275	-0.009576	9.820364	0.048363	0.088332	-0.033974
+7.235172	0.009576	0.009576	9.774877	0.045832	0.088732	-0.033308
+7.236181	-0.033517	-0.045487	9.782060	0.046897	0.089398	-0.034640
+7.237186	0.035911	-0.004788	9.760513	0.048629	0.084469	-0.035440
+7.238265	0.014364	0.004788	9.777271	0.049162	0.083536	-0.036905
+7.239206	-0.031123	-0.007182	9.856275	0.049029	0.084868	-0.034374
+7.240186	0.040699	0.009576	9.832334	0.047697	0.086334	-0.031043
+7.241207	-0.023940	0.028729	9.755725	0.049162	0.088332	-0.033041
+7.242266	-0.038305	0.019152	9.746149	0.049695	0.087666	-0.033441
+7.243265	-0.011970	0.074215	9.889792	0.048496	0.088466	-0.038770
+7.244263	0.028729	0.035911	9.844305	0.048363	0.087933	-0.042234
+7.245263	0.002394	-0.021546	9.767695	0.047963	0.089665	-0.038904
+7.246235	-0.014364	0.007182	9.743755	0.046364	0.089665	-0.035040
+7.247264	-0.040699	0.031123	9.760513	0.047697	0.088332	-0.032908
+7.248265	-0.035911	0.016758	9.748543	0.046897	0.086334	-0.036905
+7.249179	0.050275	-0.043093	9.796424	0.046231	0.088732	-0.035573
+7.250182	0.002394	-0.055063	9.815576	0.045698	0.088998	-0.034374
+7.251192	-0.023940	0.038305	9.796424	0.046098	0.087533	-0.034240
+7.252234	-0.021546	0.035911	9.748543	0.047430	0.086734	-0.033041
+7.253227	-0.014364	0.026334	9.741361	0.049429	0.087000	-0.035306
+7.254217	0.033517	0.009576	9.712632	0.049162	0.088732	-0.039303
+7.255239	-0.031123	0.069427	9.772483	0.046631	0.089132	-0.037038
+7.256228	0.000000	0.055063	9.839517	0.045165	0.088599	-0.037305
+7.257234	0.011970	0.007182	9.770089	0.045698	0.091130	-0.036372
+7.258263	0.011970	-0.004788	9.813182	0.047430	0.088865	-0.037305
+7.259264	-0.035911	0.009576	9.810788	0.047830	0.086600	-0.035173
+7.260274	0.004788	-0.047881	9.817970	0.047564	0.087400	-0.036372
+7.261239	0.016758	-0.019152	9.820364	0.043966	0.089531	-0.037571
+7.262242	-0.004788	-0.014364	9.774877	0.045032	0.087133	-0.035306
+7.263239	0.011970	0.031123	9.858669	0.046364	0.087133	-0.040369
+7.264239	-0.009576	-0.009576	9.786848	0.044899	0.085934	-0.039836
+7.265238	0.019152	-0.064639	9.782060	0.047031	0.086334	-0.035173
+7.266208	-0.033517	-0.045487	9.822758	0.047297	0.086067	-0.037038
+7.267154	-0.011970	-0.007182	9.798818	0.046364	0.088066	-0.035440
+7.268133	0.019152	0.007182	9.786848	0.047430	0.091796	-0.038237
+7.269161	-0.007182	-0.040699	9.815576	0.047830	0.092462	-0.038504
+7.270158	-0.038305	-0.050275	9.834729	0.046897	0.089931	-0.033175
+7.271162	0.011970	-0.031123	9.777271	0.045299	0.087933	-0.033974
+7.272161	-0.002394	0.035911	9.853881	0.044766	0.087799	-0.037838
+7.273164	-0.004788	-0.004788	9.820364	0.047830	0.088466	-0.037438
+7.274159	-0.004788	0.002394	9.806000	0.049296	0.090464	-0.037971
+7.275161	-0.045487	-0.040699	9.844305	0.046098	0.089665	-0.039703
+7.276156	0.002394	-0.045487	9.825152	0.045565	0.089665	-0.039969
+7.277157	-0.014364	-0.055063	9.753331	0.048629	0.088066	-0.037571
+7.278158	0.031123	-0.052669	9.770089	0.047164	0.085934	-0.037438
+7.279161	0.062245	-0.016758	9.726997	0.045432	0.085534	-0.034907
+7.280165	0.004788	0.009576	9.774877	0.047963	0.087000	-0.035839
+7.281164	0.009576	0.023940	9.760513	0.049828	0.087933	-0.033841
+7.282144	-0.026334	0.004788	9.779666	0.050361	0.088732	-0.035839
+7.283164	0.009576	-0.007182	9.798818	0.047297	0.088998	-0.037838
+7.284161	0.009576	-0.055063	9.789242	0.047564	0.089265	-0.037838
+7.285160	0.079003	-0.014364	9.822758	0.046897	0.087533	-0.035440
+7.286158	0.002394	0.007182	9.794030	0.046764	0.087266	-0.034507
+7.287161	0.055063	0.045487	9.815576	0.047430	0.088998	-0.033308
+7.288160	0.028729	-0.019152	9.880215	0.045965	0.090064	-0.038104
+7.289162	-0.009576	0.004788	9.810788	0.045965	0.089132	-0.039703
+7.290162	-0.016758	0.031123	9.837123	0.043700	0.088732	-0.039303
+7.291161	-0.014364	0.007182	9.782060	0.043833	0.086867	-0.036772
+7.292160	0.016758	0.023940	9.839517	0.047564	0.087666	-0.031576
+7.293162	0.002394	0.002394	9.760513	0.046231	0.088732	-0.032375
+7.294156	0.021546	-0.009576	9.829940	0.046098	0.090864	-0.038371
+7.295160	-0.004788	0.019152	9.889792	0.048096	0.089931	-0.042501
+7.296162	-0.021546	-0.002394	9.765301	0.047697	0.087000	-0.039703
+7.297161	-0.004788	-0.007182	9.741361	0.047297	0.087666	-0.038371
+7.298152	0.023940	-0.016758	9.695874	0.047031	0.087133	-0.034773
+7.299157	0.009576	-0.007182	9.707844	0.045565	0.085934	-0.034240
+7.300155	0.033517	-0.026334	9.832334	0.046631	0.085934	-0.036772
+7.301157	0.009576	-0.014364	9.813182	0.046231	0.088332	-0.037305
+7.302156	-0.007182	0.047881	9.738967	0.045832	0.088466	-0.037971
+7.303145	-0.057457	-0.023940	9.798818	0.045832	0.087266	-0.037571
+7.304152	0.014364	-0.033517	9.880215	0.047963	0.087133	-0.037971
+7.305153	0.033517	-0.023940	9.894580	0.048629	0.089798	-0.033441
+7.306157	-0.004788	-0.016758	9.901762	0.047697	0.090464	-0.033974
+7.307155	0.000000	-0.007182	9.755725	0.048230	0.089132	-0.035306
+7.308155	0.014364	0.026334	9.743755	0.047164	0.085268	-0.037305
+7.309152	-0.004788	-0.014364	9.803606	0.044366	0.087000	-0.037305
+7.310156	-0.014364	0.002394	9.726997	0.043833	0.087666	-0.036505
+7.311150	0.009576	0.000000	9.779666	0.046631	0.087533	-0.035972
+7.312150	0.000000	-0.023940	9.817970	0.046364	0.086600	-0.039170
+7.313155	-0.021546	-0.038305	9.758119	0.047031	0.086600	-0.038637
+7.314155	0.016758	-0.033517	9.796424	0.046231	0.087533	-0.036239
+7.315152	0.002394	-0.055063	9.786848	0.045165	0.088466	-0.035306
+7.316156	0.002394	-0.016758	9.849093	0.047031	0.088332	-0.036905
+7.317150	-0.004788	-0.002394	9.837123	0.048496	0.089265	-0.036772
+7.318157	-0.002394	0.021546	9.817970	0.045032	0.087799	-0.037305
+7.319155	0.004788	0.050275	9.808394	0.046364	0.088599	-0.039436
+7.320155	-0.016758	-0.007182	9.762907	0.049029	0.088865	-0.036372
+7.321153	-0.023940	-0.035911	9.796424	0.047963	0.089132	-0.033175
+7.322150	0.004788	-0.026334	9.822758	0.046364	0.087533	-0.032109
+7.323145	0.059851	0.016758	9.858669	0.045165	0.088466	-0.035839
+7.324152	0.062245	0.028729	9.837123	0.045032	0.087000	-0.034240
+7.325156	-0.016758	-0.028729	9.844305	0.046498	0.086734	-0.031576
+7.326161	0.043093	0.043093	9.808394	0.047830	0.088332	-0.033708
+7.327156	0.055063	0.014364	9.774877	0.045832	0.087933	-0.037438
+7.328156	0.007182	0.033517	9.794030	0.044632	0.088199	-0.038504
+7.329157	0.004788	0.038305	9.827546	0.044233	0.089398	-0.036772
+7.330128	0.002394	0.057457	9.801212	0.042634	0.088466	-0.035306
+7.331156	0.028729	-0.019152	9.827546	0.044100	0.090864	-0.035972
+7.332150	0.071821	-0.045487	9.837123	0.046498	0.091930	-0.038504
+7.333150	0.000000	0.021546	9.803606	0.048496	0.089931	-0.042501
+7.334176	-0.028729	-0.002394	9.782060	0.048096	0.087133	-0.039703
+7.335236	0.000000	-0.021546	9.832334	0.047297	0.086867	-0.037838
+7.336176	0.038305	0.000000	9.803606	0.045698	0.086734	-0.038904
+7.337190	-0.002394	0.016758	9.794030	0.046364	0.086734	-0.037838
+7.338195	0.007182	-0.023940	9.777271	0.047430	0.086600	-0.036106
+7.339190	-0.014364	-0.019152	9.853881	0.046364	0.088998	-0.035173
+7.340187	-0.016758	-0.043093	9.853881	0.048230	0.087933	-0.036905
+7.341187	-0.004788	-0.033517	9.796424	0.048230	0.085934	-0.038104
+7.342188	0.019152	-0.026334	9.703056	0.048096	0.087933	-0.037438
+7.343187	0.002394	-0.004788	9.700662	0.049029	0.091130	-0.036372
+7.344189	0.050275	-0.028729	9.758119	0.048096	0.089265	-0.035706
+7.345237	0.035911	0.016758	9.803606	0.046631	0.086867	-0.035573
+7.346235	-0.019152	-0.004788	9.820364	0.048496	0.084335	-0.039570
+7.347234	0.021546	-0.047881	9.796424	0.045965	0.084602	-0.039037
+7.348189	0.026334	-0.081397	9.846699	0.042368	0.087400	-0.037172
+7.349220	0.014364	-0.057457	9.784454	0.043567	0.090997	-0.036372
+7.350152	0.023940	-0.057457	9.736573	0.047031	0.090064	-0.037172
+7.351232	0.028729	-0.031123	9.719814	0.048763	0.087266	-0.037571
+7.352194	-0.019152	0.016758	9.849093	0.047564	0.084335	-0.040103
+7.353240	-0.004788	-0.038305	9.844305	0.045432	0.085401	-0.037305
+7.354198	0.083792	-0.023940	9.758119	0.045698	0.087533	-0.034773
+7.355195	0.052669	-0.011970	9.798818	0.047164	0.089531	-0.033308
+7.356187	-0.019152	-0.019152	9.820364	0.044899	0.088599	-0.035306
+7.357189	-0.021546	-0.040699	9.738967	0.045565	0.089798	-0.037971
+7.358229	-0.007182	-0.014364	9.765301	0.045832	0.090198	-0.039703
+7.359231	0.043093	0.016758	9.820364	0.046764	0.087666	-0.034374
+7.360230	-0.026334	-0.011970	9.827546	0.044766	0.090198	-0.031176
+7.361200	-0.004788	-0.055063	9.815576	0.043700	0.088466	-0.035706
+7.362197	-0.002394	-0.031123	9.889792	0.045432	0.086067	-0.035173
+7.363232	0.009576	0.009576	9.779666	0.047031	0.087133	-0.037038
+7.364235	-0.026334	-0.026334	9.801212	0.047963	0.087666	-0.037038
+7.365229	0.002394	-0.016758	9.798818	0.048629	0.089531	-0.038237
+7.366233	-0.009576	-0.023940	9.832334	0.047564	0.088599	-0.039836
+7.367232	0.011970	-0.033517	9.815576	0.047031	0.084469	-0.037172
+7.368169	0.011970	-0.033517	9.726997	0.047963	0.084335	-0.036505
+7.369233	-0.050275	0.002394	9.717420	0.046631	0.086334	-0.037571
+7.370232	0.009576	-0.004788	9.834729	0.047963	0.085135	-0.039969
+7.371233	0.052669	-0.047881	9.825152	0.046897	0.086067	-0.039836
+7.372200	0.000000	-0.014364	9.808394	0.045165	0.085002	-0.035040
+7.373234	0.004788	-0.019152	9.841911	0.046231	0.086734	-0.034907
+7.374233	-0.007182	-0.031123	9.786848	0.047164	0.087799	-0.034374
+7.375233	-0.011970	-0.007182	9.870639	0.049962	0.087799	-0.032508
+7.376232	0.055063	-0.038305	9.846699	0.049962	0.088865	-0.036639
+7.377226	-0.009576	-0.031123	9.753331	0.049695	0.090198	-0.039303
+7.378174	-0.033517	-0.038305	9.815576	0.046897	0.089531	-0.034773
+7.379176	-0.050275	0.004788	9.817970	0.045299	0.089798	-0.035573
+7.380136	-0.007182	0.019152	9.839517	0.045299	0.088466	-0.036239
+7.381228	0.004788	0.007182	9.806000	0.043833	0.086867	-0.037838
+7.382204	0.002394	0.009576	9.822758	0.047031	0.085401	-0.033841
+7.383186	0.014364	0.040699	9.851487	0.049162	0.086201	-0.035839
+7.384175	0.007182	0.014364	9.829940	0.047297	0.085534	-0.036239
+7.385153	0.016758	0.002394	9.762907	0.046631	0.086467	-0.034773
+7.386155	0.035911	0.026334	9.846699	0.046764	0.085002	-0.037438
+7.387173	0.059851	0.023940	9.834729	0.045698	0.087000	-0.036372
+7.388173	0.079003	-0.016758	9.698268	0.047564	0.088865	-0.037172
+7.389170	0.011970	0.014364	9.841911	0.048363	0.089398	-0.036372
+7.390233	0.002394	0.035911	9.870639	0.046098	0.087933	-0.037038
+7.391171	-0.019152	0.026334	9.856275	0.045832	0.085401	-0.036639
+7.392167	-0.038305	-0.016758	9.741361	0.049429	0.088599	-0.036106
+7.393163	-0.004788	-0.016758	9.738967	0.049162	0.087533	-0.035706
+7.394136	-0.019152	-0.023940	9.789242	0.047963	0.086467	-0.039037
+7.395165	-0.028729	-0.031123	9.841911	0.047164	0.088199	-0.040236
+7.396160	-0.038305	-0.002394	9.853881	0.048230	0.085401	-0.037305
+7.397182	-0.011970	0.000000	9.767695	0.046764	0.087400	-0.036905
+7.398166	-0.002394	0.007182	9.791636	0.045965	0.090331	-0.035573
+7.399187	0.016758	0.028729	9.813182	0.046098	0.091130	-0.034107
+7.400186	0.038305	0.009576	9.849093	0.046897	0.086334	-0.036106
+7.401188	0.038305	0.002394	9.810788	0.045432	0.085668	-0.035573
+7.402230	-0.007182	0.011970	9.880215	0.042501	0.088732	-0.035972
+7.403187	0.014364	-0.035911	9.861063	0.045565	0.089665	-0.035173
+7.404184	-0.004788	-0.031123	9.822758	0.048496	0.088599	-0.037305
+7.405186	-0.016758	-0.028729	9.784454	0.050894	0.088199	-0.036372
+7.406234	0.023940	-0.057457	9.839517	0.048363	0.087400	-0.036239
+7.407220	0.064639	-0.016758	9.851487	0.045432	0.087266	-0.035839
+7.408233	0.021546	-0.021546	9.944854	0.044766	0.087933	-0.035573
+7.409202	0.059851	-0.050275	9.794030	0.046631	0.089132	-0.034773
+7.410199	0.033517	0.026334	9.724603	0.048096	0.090198	-0.035440
+7.411226	-0.031123	-0.019152	9.715026	0.050228	0.088199	-0.036505
+7.412232	0.007182	0.000000	9.753331	0.048363	0.087533	-0.036505
+7.413233	0.007182	0.004788	9.853881	0.046897	0.084735	-0.036905
+7.414234	-0.009576	-0.019152	9.779666	0.046897	0.088466	-0.034507
+7.415188	0.023940	0.028729	9.784454	0.047031	0.090198	-0.039170
+7.416166	-0.007182	0.009576	9.841911	0.047564	0.088466	-0.038770
+7.417167	0.009576	-0.045487	9.817970	0.046231	0.085401	-0.032775
+7.418160	0.050275	0.014364	9.841911	0.048096	0.085534	-0.034907
+7.419187	0.033517	0.021546	9.844305	0.046231	0.086334	-0.039836
+7.420182	0.031123	0.007182	9.741361	0.045032	0.089265	-0.040502
+7.421170	-0.023940	0.064639	9.774877	0.046631	0.088865	-0.039436
+7.422254	0.009576	0.028729	9.760513	0.047697	0.086334	-0.038770
+7.423189	0.002394	-0.002394	9.755725	0.047297	0.086867	-0.038504
+7.424189	-0.021546	0.040699	9.777271	0.047697	0.088865	-0.039836
+7.425191	-0.002394	0.000000	9.750937	0.049162	0.088998	-0.037305
+7.426233	0.011970	0.050275	9.786848	0.046098	0.089798	-0.038770
+7.427230	0.079003	-0.026334	9.743755	0.042767	0.089398	-0.039436
+7.428188	0.009576	-0.021546	9.734179	0.045032	0.088865	-0.037438
+7.429227	-0.040699	0.031123	9.755725	0.047697	0.089798	-0.035440
+7.430172	0.011970	0.045487	9.770089	0.048096	0.091663	-0.033441
+7.431212	0.016758	-0.007182	9.832334	0.048230	0.090064	-0.034907
+7.432228	-0.014364	0.002394	9.750937	0.049296	0.088732	-0.036505
+7.433233	0.007182	0.009576	9.729391	0.048763	0.084202	-0.036106
+7.434228	0.045487	0.009576	9.726997	0.045032	0.085268	-0.036106
+7.435191	0.055063	-0.026334	9.810788	0.045299	0.087799	-0.039436
+7.436232	0.043093	-0.028729	9.820364	0.048763	0.087000	-0.036106
+7.437226	0.009576	0.016758	9.829940	0.049429	0.087799	-0.035040
+7.438232	0.000000	0.035911	9.798818	0.049296	0.087400	-0.033574
+7.439232	0.067033	0.057457	9.810788	0.046498	0.087133	-0.036639
+7.440232	0.043093	0.016758	9.846699	0.046364	0.090597	-0.037704
+7.441218	0.004788	0.004788	9.851487	0.044632	0.092063	-0.038104
+7.442236	0.004788	-0.081397	9.822758	0.048230	0.089931	-0.038904
+7.443232	0.055063	0.000000	9.758119	0.048763	0.088732	-0.036239
+7.444230	0.026334	0.021546	9.724603	0.048896	0.086067	-0.033175
+7.445231	-0.050275	0.002394	9.712632	0.047164	0.088066	-0.033841
+7.446229	0.014364	-0.031123	9.762907	0.045965	0.089265	-0.036239
+7.447185	0.019152	0.040699	9.806000	0.044366	0.086734	-0.038371
+7.448188	-0.019152	0.014364	9.885003	0.046631	0.089665	-0.038904
+7.449190	-0.040699	-0.038305	9.894580	0.049296	0.090331	-0.037838
+7.450221	-0.019152	-0.011970	9.772483	0.048363	0.089531	-0.038237
+7.451192	0.038305	0.021546	9.789242	0.046231	0.088199	-0.036772
+7.452213	0.035911	-0.023940	9.815576	0.045565	0.089132	-0.035573
+7.453216	0.047881	-0.035911	9.765301	0.045965	0.088599	-0.036505
+7.454234	0.016758	-0.038305	9.784454	0.049029	0.087133	-0.037172
+7.455228	0.004788	-0.004788	9.779666	0.048363	0.088332	-0.036639
+7.456230	0.009576	0.019152	9.794030	0.048496	0.089398	-0.037038
+7.457230	0.004788	0.057457	9.839517	0.046231	0.086201	-0.036372
+7.458231	0.004788	0.057457	9.839517	0.044899	0.085934	-0.038904
+7.459216	0.014364	0.028729	9.770089	0.045299	0.087266	-0.034907
+7.460231	-0.004788	0.004788	9.770089	0.046364	0.086334	-0.034640
+7.461230	-0.009576	0.002394	9.829940	0.045165	0.085668	-0.036772
+7.462230	0.009576	-0.031123	9.789242	0.045165	0.088332	-0.037838
+7.463170	0.035911	-0.021546	9.817970	0.047830	0.089665	-0.040236
+7.464226	0.016758	0.021546	9.827546	0.050628	0.089531	-0.039703
+7.465232	-0.026334	0.038305	9.892186	0.047830	0.089398	-0.038237
+7.466232	-0.004788	0.009576	9.825152	0.045565	0.089931	-0.036106
+7.467230	-0.004788	0.021546	9.791636	0.047164	0.089798	-0.034107
+7.468193	-0.028729	0.016758	9.820364	0.047297	0.087533	-0.033441
+7.469230	0.031123	0.021546	9.820364	0.045698	0.085668	-0.033441
+7.470232	-0.011970	0.014364	9.784454	0.046897	0.089398	-0.034907
+7.471221	-0.021546	0.057457	9.789242	0.047031	0.088998	-0.035573
+7.472212	0.019152	0.035911	9.777271	0.047031	0.086867	-0.033974
+7.473247	-0.033517	0.019152	9.837123	0.048763	0.087533	-0.033708
+7.474232	0.033517	-0.011970	9.762907	0.049296	0.088732	-0.034507
+7.475231	0.031123	0.016758	9.755725	0.047963	0.088332	-0.036372
+7.476224	0.021546	0.043093	9.791636	0.047164	0.088865	-0.038504
+7.477172	0.033517	0.019152	9.832334	0.045032	0.088199	-0.034240
+7.478174	0.021546	0.071821	9.784454	0.045832	0.087400	-0.033974
+7.479227	-0.009576	0.009576	9.817970	0.047564	0.086334	-0.034240
+7.480224	-0.014364	-0.047881	9.789242	0.047830	0.087799	-0.034640
+7.481233	-0.035911	0.011970	9.755725	0.047297	0.088466	-0.036505
+7.482204	-0.052669	-0.004788	9.746149	0.046364	0.088599	-0.036772
+7.483211	-0.023940	0.014364	9.808394	0.046631	0.089398	-0.035306
+7.484251	0.014364	0.004788	9.784454	0.045832	0.089798	-0.035839
+7.485174	0.014364	-0.004788	9.786848	0.046498	0.091930	-0.035839
+7.486233	0.000000	-0.026334	9.834729	0.047031	0.090597	-0.035706
+7.487230	0.031123	0.004788	9.827546	0.048230	0.088332	-0.035040
+7.488228	0.028729	-0.004788	9.817970	0.049429	0.086067	-0.036106
+7.489230	0.021546	-0.026334	9.813182	0.048363	0.087799	-0.039037
+7.490231	0.004788	0.011970	9.791636	0.046498	0.089665	-0.036639
+7.491159	0.045487	0.014364	9.772483	0.046231	0.089665	-0.037172
+7.492154	0.004788	0.009576	9.753331	0.044899	0.086600	-0.036639
+7.493184	-0.062245	-0.016758	9.758119	0.045698	0.087666	-0.037172
+7.494185	0.000000	0.014364	9.829940	0.048629	0.089665	-0.032908
+7.495190	-0.011970	0.047881	9.846699	0.046098	0.090198	-0.035706
+7.496173	-0.033517	0.021546	9.858669	0.044233	0.088599	-0.037038
+7.497187	-0.009576	-0.007182	9.822758	0.046764	0.087133	-0.035706
+7.498182	0.016758	0.011970	9.806000	0.048896	0.084735	-0.036239
+7.499231	0.055063	0.019152	9.899368	0.047830	0.085801	-0.035173
+7.500230	0.102944	0.062245	9.861063	0.048363	0.087799	-0.033708
+7.501166	0.019152	0.021546	9.858669	0.047564	0.087133	-0.033308
+7.502232	-0.004788	-0.007182	9.789242	0.047164	0.087133	-0.031975
+7.503229	-0.014364	0.007182	9.741361	0.046498	0.086334	-0.034374
+7.504231	-0.004788	-0.011970	9.786848	0.046498	0.086067	-0.034640
+7.505216	-0.019152	-0.062245	9.829940	0.045832	0.087666	-0.035040
+7.506223	-0.023940	-0.045487	9.815576	0.048496	0.088599	-0.037038
+7.507228	-0.004788	-0.038305	9.770089	0.046764	0.088865	-0.039703
+7.508231	0.016758	-0.014364	9.772483	0.044899	0.087666	-0.037438
+7.509231	0.019152	-0.016758	9.770089	0.047830	0.085268	-0.034240
+7.510232	-0.019152	-0.007182	9.791636	0.046897	0.085135	-0.035839
+7.511219	-0.028729	-0.028729	9.760513	0.047564	0.086201	-0.035440
+7.512232	0.052669	-0.026334	9.784454	0.046764	0.085534	-0.033841
+7.513230	0.023940	-0.033517	9.815576	0.045565	0.087933	-0.033308
+7.514198	0.038305	-0.059851	9.806000	0.044899	0.088332	-0.033708
+7.515191	0.000000	-0.021546	9.832334	0.046231	0.085801	-0.034507
+7.516216	-0.038305	-0.019152	9.806000	0.048096	0.087000	-0.036905
+7.517170	-0.011970	0.002394	9.806000	0.048363	0.086600	-0.037571
+7.518154	-0.033517	-0.009576	9.853881	0.047963	0.086334	-0.037838
+7.519180	0.035911	0.023940	9.791636	0.045698	0.087266	-0.034640
+7.520185	0.011970	-0.009576	9.731785	0.044899	0.089132	-0.033574
+7.521185	-0.009576	0.043093	9.808394	0.046897	0.089931	-0.037838
+7.522185	0.009576	0.021546	9.777271	0.046897	0.088466	-0.037704
+7.523183	0.021546	0.023940	9.729391	0.046631	0.088199	-0.037172
+7.524180	0.014364	0.031123	9.810788	0.048496	0.086734	-0.037571
+7.525184	0.007182	-0.040699	9.822758	0.049695	0.087933	-0.037571
+7.526216	0.026334	-0.043093	9.815576	0.046231	0.086467	-0.038504
+7.527189	-0.026334	0.043093	9.889792	0.046897	0.088332	-0.036639
+7.528253	0.011970	0.021546	9.940066	0.047031	0.090997	-0.033974
+7.529187	0.033517	0.011970	9.837123	0.045965	0.090198	-0.033441
+7.530187	0.040699	-0.028729	9.734179	0.046098	0.088199	-0.036106
+7.531183	0.021546	-0.076609	9.801212	0.046764	0.085268	-0.036239
+7.532151	0.028729	-0.074215	9.856275	0.046364	0.086600	-0.039703
+7.533185	0.011970	0.000000	9.896974	0.048496	0.088732	-0.039436
+7.534184	0.000000	0.045487	9.796424	0.051294	0.088998	-0.035440
+7.535231	0.014364	0.000000	9.782060	0.049695	0.086067	-0.035040
+7.536229	-0.002394	-0.031123	9.743755	0.043167	0.084469	-0.035839
+7.537232	-0.002394	0.031123	9.873033	0.041435	0.087000	-0.036639
+7.538216	0.004788	-0.019152	9.849093	0.046098	0.089931	-0.038637
+7.539201	-0.004788	-0.021546	9.731785	0.049828	0.086067	-0.037838
+7.540215	-0.016758	-0.011970	9.825152	0.048763	0.086201	-0.038504
+7.541229	-0.026334	-0.028729	9.817970	0.046231	0.086867	-0.034374
+7.542199	0.019152	0.033517	9.762907	0.044366	0.089265	-0.035839
+7.543230	0.088580	0.059851	9.698268	0.044366	0.089398	-0.038237
+7.544231	0.059851	0.023940	9.734179	0.046764	0.088199	-0.040103
+7.545211	0.045487	-0.019152	9.841911	0.045698	0.088732	-0.038637
+7.546229	-0.021546	-0.043093	9.820364	0.048096	0.088199	-0.036772
+7.547166	0.009576	-0.031123	9.734179	0.046231	0.086734	-0.035440
+7.548184	0.021546	0.045487	9.794030	0.046631	0.087400	-0.037838
+7.549229	0.026334	-0.059851	9.813182	0.048496	0.087133	-0.038637
+7.550165	-0.062245	0.002394	9.750937	0.047697	0.088332	-0.038770
+7.551251	-0.055063	-0.047881	9.698268	0.049162	0.088732	-0.039303
+7.552190	-0.057457	0.009576	9.738967	0.047430	0.085934	-0.036639
+7.553231	-0.047881	-0.009576	9.762907	0.043966	0.082337	-0.036505
+7.554214	-0.011970	-0.011970	9.837123	0.044499	0.084868	-0.035440
+7.555227	0.021546	0.038305	9.865851	0.047430	0.086334	-0.036639
+7.556231	-0.023940	0.002394	9.803606	0.049828	0.086867	-0.037838
+7.557231	0.011970	-0.033517	9.798818	0.049695	0.086600	-0.038504
+7.558231	0.047881	-0.016758	9.786848	0.049695	0.086467	-0.034773
+7.559225	0.069427	-0.045487	9.717420	0.047830	0.088466	-0.036372
+7.560210	0.028729	-0.011970	9.784454	0.046498	0.087666	-0.035040
+7.561253	0.033517	-0.019152	9.734179	0.048230	0.085934	-0.035173
+7.562231	0.062245	-0.050275	9.729391	0.049296	0.088332	-0.039037
+7.563231	0.035911	0.002394	9.770089	0.048096	0.088732	-0.039836
+7.564229	0.011970	0.000000	9.803606	0.045965	0.089132	-0.040236
+7.565230	0.033517	-0.016758	9.822758	0.047031	0.089931	-0.038237
+7.566231	-0.002394	0.021546	9.829940	0.045965	0.091397	-0.036372
+7.567228	0.057457	-0.011970	9.789242	0.046631	0.089531	-0.035972
+7.568230	0.014364	-0.026334	9.765301	0.045432	0.086734	-0.036905
+7.569231	-0.011970	0.033517	9.748543	0.045565	0.086867	-0.037438
+7.570229	-0.009576	0.040699	9.758119	0.045965	0.087133	-0.032242
+7.571178	-0.011970	0.035911	9.777271	0.045698	0.087000	-0.033308
+7.572247	0.028729	0.028729	9.774877	0.045698	0.085934	-0.034640
+7.573231	0.028729	0.031123	9.913732	0.045698	0.085801	-0.037438
+7.574232	-0.021546	-0.011970	9.863457	0.047830	0.088066	-0.038237
+7.575230	0.011970	0.007182	9.750937	0.046897	0.086600	-0.038904
+7.576211	0.007182	-0.023940	9.784454	0.048363	0.087266	-0.036372
+7.577230	-0.004788	-0.011970	9.815576	0.048230	0.087666	-0.036905
+7.578174	0.031123	-0.007182	9.940066	0.047430	0.088199	-0.037438
+7.579230	0.019152	0.014364	9.801212	0.047697	0.087400	-0.034507
+7.580230	0.021546	-0.057457	9.703056	0.045698	0.087799	-0.035706
+7.581195	0.040699	-0.074215	9.734179	0.044899	0.088865	-0.035173
+7.582171	0.081397	-0.031123	9.803606	0.044233	0.090198	-0.033441
+7.583228	0.011970	-0.033517	9.782060	0.045965	0.088865	-0.037571
+7.584230	0.052669	-0.009576	9.798818	0.045165	0.086467	-0.035706
+7.585173	0.038305	-0.040699	9.834729	0.047697	0.085801	-0.033441
+7.586226	-0.040699	-0.021546	9.810788	0.049562	0.087666	-0.036372
+7.587230	0.021546	0.009576	9.820364	0.049296	0.088998	-0.038371
+7.588226	-0.028729	-0.023940	9.868245	0.044632	0.090331	-0.037172
+7.589186	-0.045487	-0.052669	9.849093	0.045165	0.088066	-0.034640
+7.590184	-0.064639	0.023940	9.779666	0.047830	0.084202	-0.035839
+7.591182	-0.028729	-0.045487	9.760513	0.047164	0.086201	-0.036772
+7.592184	0.035911	-0.021546	9.801212	0.046231	0.089398	-0.035040
+7.593180	0.071821	-0.038305	9.827546	0.045698	0.089531	-0.034240
+7.594179	0.059851	-0.026334	9.801212	0.047830	0.086734	-0.034507
+7.595183	0.016758	0.031123	9.794030	0.047697	0.088066	-0.036106
+7.596183	0.026334	0.016758	9.801212	0.045965	0.089132	-0.039037
+7.597179	0.028729	0.079003	9.815576	0.045165	0.089398	-0.038770
+7.598183	0.050275	-0.007182	9.846699	0.047697	0.089132	-0.033841
+7.599165	0.033517	-0.031123	9.868245	0.045698	0.086600	-0.031842
+7.600183	0.002394	-0.059851	9.853881	0.045698	0.087266	-0.034240
+7.601190	0.043093	-0.040699	9.815576	0.046231	0.086201	-0.039170
+7.602167	0.014364	-0.033517	9.806000	0.047564	0.087933	-0.039703
+7.603214	0.011970	-0.019152	9.741361	0.047564	0.087933	-0.037038
+7.604185	0.059851	-0.019152	9.734179	0.046631	0.087666	-0.038504
+7.605185	0.016758	-0.033517	9.703056	0.045432	0.087400	-0.037704
+7.606229	0.043093	-0.033517	9.712632	0.046098	0.086467	-0.033308
+7.607187	-0.023940	0.035911	9.803606	0.047697	0.086867	-0.031043
+7.608186	-0.045487	0.023940	9.822758	0.049162	0.087266	-0.033441
+7.609194	-0.028729	0.040699	9.791636	0.047697	0.087266	-0.035573
+7.610184	0.019152	0.067033	9.801212	0.045432	0.087533	-0.035839
+7.611164	0.059851	0.038305	9.784454	0.045432	0.086867	-0.037704
+7.612175	0.038305	-0.055063	9.825152	0.047830	0.086867	-0.035706
+7.613229	0.059851	-0.004788	9.774877	0.048629	0.088732	-0.036772
+7.614229	0.043093	0.071821	9.767695	0.046364	0.088332	-0.035573
+7.615213	0.040699	-0.016758	9.779666	0.045299	0.088732	-0.034507
+7.616246	0.014364	-0.040699	9.753331	0.044766	0.090597	-0.036372
+7.617231	0.011970	0.016758	9.765301	0.046631	0.090597	-0.035306
+7.618164	0.055063	0.000000	9.743755	0.047297	0.090464	-0.033574
+7.619225	0.021546	0.004788	9.724603	0.046364	0.085534	-0.034640
+7.620226	-0.035911	-0.009576	9.647993	0.047164	0.084602	-0.033708
+7.621228	-0.026334	-0.033517	9.782060	0.047164	0.085934	-0.038637
+7.622230	0.009576	-0.011970	9.892186	0.049029	0.085668	-0.036905
+7.623229	0.007182	-0.033517	9.844305	0.045832	0.086334	-0.036639
+7.624226	0.009576	-0.016758	9.798818	0.045165	0.085934	-0.039969
+7.625195	0.019152	0.043093	9.868245	0.046498	0.085801	-0.039969
+7.626217	0.062245	-0.009576	9.844305	0.048896	0.086067	-0.037704
+7.627232	0.052669	-0.033517	9.815576	0.049296	0.086067	-0.036239
+7.628228	0.033517	-0.035911	9.832334	0.047031	0.086067	-0.038104
+7.629229	-0.035911	-0.023940	9.746149	0.046631	0.085268	-0.037838
+7.630172	-0.004788	-0.035911	9.815576	0.048230	0.088599	-0.035972
+7.631186	0.000000	-0.057457	9.865851	0.047697	0.090064	-0.038237
+7.632222	0.014364	-0.052669	9.858669	0.047031	0.087133	-0.037571
+7.633231	0.019152	0.021546	9.858669	0.049828	0.086467	-0.036239
+7.634232	0.009576	0.023940	9.861063	0.048763	0.087799	-0.033841
+7.635203	0.019152	0.067033	9.806000	0.046098	0.085934	-0.033308
+7.636227	0.009576	-0.035911	9.861063	0.044899	0.086334	-0.035839
+7.637261	0.016758	-0.021546	9.880215	0.044366	0.085002	-0.033708
+7.638208	0.052669	0.004788	9.853881	0.046498	0.087799	-0.036639
+7.639232	0.019152	0.002394	9.806000	0.047963	0.089798	-0.038504
+7.640231	-0.016758	-0.009576	9.858669	0.047430	0.087000	-0.036239
+7.641193	-0.035911	-0.021546	9.894580	0.046764	0.086867	-0.037172
+7.642190	-0.009576	-0.038305	9.806000	0.045565	0.088998	-0.038904
+7.643233	-0.043093	-0.004788	9.853881	0.044632	0.085534	-0.037838
+7.644232	0.016758	0.002394	9.896974	0.046764	0.083669	-0.036106
+7.645214	0.016758	-0.062245	9.829940	0.047031	0.084335	-0.035706
+7.646221	-0.035911	-0.002394	9.729391	0.047564	0.087533	-0.036106
+7.647209	0.016758	-0.016758	9.777271	0.045965	0.088599	-0.037838
+7.648169	-0.011970	0.028729	9.825152	0.045965	0.088998	-0.037704
+7.649185	0.009576	0.000000	9.789242	0.045165	0.089531	-0.036106
+7.650234	0.009576	0.009576	9.760513	0.046231	0.086067	-0.037438
+7.651234	0.064639	-0.007182	9.880215	0.047031	0.084335	-0.036639
+7.652234	0.016758	-0.009576	9.875427	0.046764	0.084602	-0.038637
+7.653233	0.011970	-0.033517	9.803606	0.046498	0.088066	-0.035440
+7.654163	0.002394	-0.007182	9.753331	0.047430	0.087933	-0.034374
+7.655233	-0.011970	0.021546	9.777271	0.047297	0.087799	-0.037438
+7.656206	-0.023940	0.059851	9.755725	0.047430	0.086867	-0.039570
+7.657172	0.000000	0.011970	9.832334	0.050495	0.086734	-0.037704
+7.658258	0.021546	-0.031123	9.806000	0.052227	0.084335	-0.033308
+7.659205	-0.033517	-0.062245	9.841911	0.049562	0.085934	-0.030110
+7.660233	-0.014364	-0.035911	9.889792	0.047564	0.087133	-0.033708
+7.661221	0.069427	-0.016758	9.873033	0.048496	0.088199	-0.035972
+7.662235	0.081397	0.000000	9.803606	0.049429	0.088599	-0.034907
+7.663233	0.052669	0.028729	9.772483	0.048096	0.087666	-0.034107
+7.664232	0.028729	-0.009576	9.849093	0.044899	0.087133	-0.033974
+7.665250	0.052669	-0.055063	9.868245	0.045565	0.087000	-0.036106
+7.666219	0.059851	-0.079003	9.815576	0.046231	0.086467	-0.033308
+7.667234	0.009576	0.016758	9.796424	0.047164	0.086600	-0.036505
+7.668233	0.052669	-0.038305	9.741361	0.045299	0.086201	-0.039436
+7.669233	-0.031123	-0.038305	9.693480	0.045165	0.087533	-0.039170
+7.670234	-0.052669	-0.040699	9.722208	0.045965	0.088998	-0.036239
+7.671234	-0.002394	-0.052669	9.765301	0.048096	0.089531	-0.033841
+7.672219	0.028729	-0.011970	9.796424	0.048763	0.087933	-0.034907
+7.673206	0.026334	-0.011970	9.801212	0.048230	0.086201	-0.038104
+7.674237	0.009576	0.011970	9.762907	0.045432	0.087666	-0.035839
+7.675234	0.038305	-0.002394	9.827546	0.043567	0.087533	-0.032908
+7.676225	0.014364	0.000000	9.782060	0.044233	0.083936	-0.036905
+7.677256	0.023940	0.038305	9.810788	0.045432	0.086067	-0.039436
+7.678177	0.074215	-0.028729	9.889792	0.045432	0.089665	-0.038904
+7.679233	0.055063	-0.033517	9.834729	0.045965	0.087266	-0.035306
+7.680232	-0.016758	0.062245	9.856275	0.045965	0.087400	-0.032908
+7.681169	-0.019152	0.047881	9.870639	0.046631	0.089798	-0.034507
+7.682234	0.031123	-0.021546	9.810788	0.047564	0.087666	-0.034240
+7.683233	0.033517	-0.004788	9.813182	0.045432	0.084069	-0.035040
+7.684234	-0.009576	-0.009576	9.762907	0.045832	0.084469	-0.037305
+7.685174	-0.002394	0.035911	9.770089	0.047564	0.087533	-0.038371
+7.686212	-0.011970	-0.004788	9.719814	0.046897	0.087799	-0.034240
+7.687213	0.038305	-0.031123	9.705450	0.045965	0.087666	-0.034907
+7.688226	0.014364	-0.009576	9.760513	0.044632	0.087133	-0.037438
+7.689204	0.050275	-0.045487	9.810788	0.044366	0.087799	-0.034907
+7.690202	0.009576	-0.074215	9.844305	0.048230	0.087799	-0.036372
+7.691202	-0.033517	0.045487	9.837123	0.050228	0.087666	-0.034907
+7.692234	0.009576	0.033517	9.755725	0.051427	0.087133	-0.037305
+7.693235	-0.007182	-0.040699	9.777271	0.047830	0.088332	-0.037305
+7.694237	-0.055063	-0.055063	9.770089	0.047031	0.089665	-0.034240
+7.695233	-0.064639	-0.019152	9.813182	0.047297	0.086600	-0.031975
+7.696232	0.028729	-0.028729	9.911338	0.046098	0.086467	-0.035706
+7.697206	0.011970	0.038305	9.896974	0.047164	0.087266	-0.036905
+7.698226	0.035911	0.050275	9.825152	0.048629	0.087266	-0.037038
+7.699217	0.076609	-0.031123	9.810788	0.047297	0.084735	-0.035573
+7.700203	0.016758	-0.002394	9.822758	0.047164	0.085401	-0.034907
+7.701233	-0.004788	0.002394	9.820364	0.048496	0.087266	-0.034107
+7.702215	0.021546	0.023940	9.825152	0.047164	0.090064	-0.033974
+7.703233	0.059851	0.043093	9.806000	0.045832	0.088199	-0.036372
+7.704185	0.045487	-0.007182	9.789242	0.045965	0.087133	-0.037704
+7.705235	0.031123	0.011970	9.794030	0.046098	0.088865	-0.037704
+7.706201	0.019152	-0.009576	9.815576	0.046098	0.087400	-0.041035
+7.707195	-0.026334	0.000000	9.851487	0.046498	0.085801	-0.040103
+7.708209	0.009576	-0.028729	9.803606	0.045965	0.088199	-0.037038
+7.709208	0.064639	-0.004788	9.794030	0.045432	0.089931	-0.033308
+7.710160	0.009576	0.009576	9.841911	0.045432	0.089531	-0.035573
+7.711230	-0.038305	-0.043093	9.875427	0.044899	0.087933	-0.036239
+7.712231	0.009576	-0.033517	9.827546	0.044899	0.086201	-0.035573
+7.713234	0.000000	-0.016758	9.832334	0.044632	0.088466	-0.035173
+7.714179	-0.014364	-0.004788	9.873033	0.044766	0.089265	-0.032375
+7.715226	0.033517	0.007182	9.784454	0.045832	0.090064	-0.037571
+7.716231	0.047881	-0.014364	9.774877	0.046098	0.088599	-0.037305
+7.717231	-0.009576	-0.021546	9.810788	0.044100	0.089398	-0.039703
+7.718147	-0.059851	0.000000	9.817970	0.045032	0.089798	-0.037305
+7.719194	-0.047881	-0.011970	9.839517	0.047164	0.087666	-0.034907
+7.720233	-0.062245	-0.019152	9.856275	0.046498	0.086201	-0.033441
+7.721234	0.028729	0.011970	9.774877	0.044899	0.089398	-0.037172
+7.722230	0.026334	-0.033517	9.726997	0.044366	0.088066	-0.038371
+7.723224	0.002394	-0.004788	9.806000	0.045032	0.087933	-0.037704
+7.724230	0.004788	0.023940	9.849093	0.048230	0.087000	-0.037038
+7.725230	0.011970	-0.045487	9.849093	0.048096	0.088865	-0.036505
+7.726232	0.004788	-0.038305	9.779666	0.046631	0.090464	-0.039436
+7.727233	0.009576	0.019152	9.748543	0.047031	0.087933	-0.035306
+7.728196	-0.002394	0.023940	9.731785	0.047164	0.085668	-0.036106
+7.729210	-0.009576	0.021546	9.801212	0.049828	0.087533	-0.038770
+7.730233	-0.004788	0.011970	9.911338	0.048763	0.089265	-0.035573
+7.731162	0.028729	-0.009576	9.841911	0.044499	0.086600	-0.031975
+7.732234	0.033517	0.007182	9.784454	0.043833	0.086334	-0.033708
+7.733230	0.004788	-0.026334	9.832334	0.045965	0.087666	-0.037305
+7.734233	0.011970	-0.040699	9.820364	0.049162	0.087666	-0.034773
+7.735177	0.021546	-0.038305	9.755725	0.049962	0.085801	-0.034374
+7.736203	-0.014364	0.002394	9.789242	0.048230	0.084868	-0.036772
+7.737171	0.035911	0.011970	9.829940	0.044100	0.088865	-0.037838
+7.738156	0.033517	0.000000	9.736573	0.043300	0.089798	-0.036372
+7.739181	0.021546	0.007182	9.789242	0.045165	0.085534	-0.035573
+7.740229	-0.014364	0.002394	9.829940	0.046498	0.085135	-0.037438
+7.741227	-0.050275	-0.023940	9.832334	0.045698	0.088865	-0.036505
+7.742208	-0.040699	-0.052669	9.770089	0.048763	0.092995	-0.036239
+7.743232	-0.021546	-0.014364	9.765301	0.049162	0.091397	-0.037704
+7.744234	0.052669	-0.028729	9.834729	0.050228	0.088599	-0.036505
+7.745236	0.011970	-0.011970	9.875427	0.047564	0.088199	-0.033974
+7.746246	0.011970	0.000000	9.837123	0.045165	0.087533	-0.033041
+7.747234	0.016758	-0.007182	9.820364	0.043300	0.087400	-0.037038
+7.748201	-0.019152	-0.016758	9.760513	0.044499	0.089398	-0.036239
+7.749191	-0.016758	0.016758	9.767695	0.047564	0.089265	-0.037971
+7.750232	0.026334	0.002394	9.846699	0.049962	0.090198	-0.038637
+7.751233	0.028729	0.028729	9.825152	0.048496	0.086734	-0.037172
+7.752234	0.050275	0.011970	9.736573	0.045832	0.085801	-0.035440
+7.753234	0.043093	0.014364	9.755725	0.046231	0.086201	-0.034907
+7.754235	-0.023940	0.002394	9.698268	0.045165	0.086334	-0.035440
+7.755173	-0.016758	0.002394	9.758119	0.045565	0.086201	-0.035440
+7.756231	-0.011970	-0.002394	9.844305	0.044366	0.085668	-0.038237
+7.757232	0.026334	0.011970	9.794030	0.046498	0.090597	-0.038770
+7.758230	-0.009576	0.035911	9.813182	0.049962	0.090464	-0.037838
+7.759210	-0.014364	-0.031123	9.762907	0.048363	0.087533	-0.037571
+7.760172	0.019152	-0.009576	9.731785	0.045698	0.085534	-0.037305
+7.761234	-0.019152	0.011970	9.748543	0.046764	0.086467	-0.038770
+7.762234	-0.007182	0.002394	9.729391	0.049429	0.086734	-0.035573
+7.763232	-0.035911	-0.016758	9.717420	0.049029	0.089665	-0.034773
+7.764232	-0.009576	-0.052669	9.750937	0.048096	0.087666	-0.034640
+7.765232	0.011970	-0.090974	9.817970	0.046231	0.086467	-0.034773
+7.766235	-0.019152	-0.038305	9.798818	0.047297	0.087533	-0.037038
+7.767204	0.033517	-0.021546	9.846699	0.047164	0.087400	-0.039170
+7.768161	0.031123	-0.011970	9.875427	0.047031	0.087933	-0.036772
+7.769203	-0.007182	-0.038305	9.851487	0.044899	0.091263	-0.035440
+7.770188	0.019152	-0.028729	9.796424	0.046098	0.091796	-0.035573
+7.771224	-0.014364	-0.021546	9.762907	0.047031	0.088865	-0.039303
+7.772206	0.009576	0.011970	9.794030	0.044632	0.085401	-0.040769
+7.773230	0.059851	-0.028729	9.813182	0.043833	0.084868	-0.037704
+7.774234	0.043093	0.050275	9.767695	0.043433	0.088466	-0.036505
+7.775230	0.028729	0.002394	9.803606	0.044233	0.088466	-0.035173
+7.776227	0.007182	-0.050275	9.853881	0.043567	0.088199	-0.036905
+7.777228	0.016758	-0.021546	9.808394	0.043966	0.088199	-0.035839
+7.778232	0.043093	-0.009576	9.817970	0.046098	0.087533	-0.035972
+7.779161	-0.035911	-0.004788	9.863457	0.046764	0.087666	-0.033041
+7.780217	-0.009576	0.002394	9.748543	0.047031	0.087266	-0.035173
+7.781154	0.033517	-0.026334	9.815576	0.047297	0.087266	-0.035173
+7.782234	0.011970	-0.007182	9.875427	0.048096	0.085934	-0.033841
+7.783179	0.007182	0.002394	9.868245	0.047297	0.086067	-0.034507
+7.784235	-0.007182	-0.064639	9.810788	0.047963	0.086201	-0.037172
+7.785171	-0.016758	-0.074215	9.767695	0.049162	0.087533	-0.036639
+7.786234	0.011970	-0.019152	9.777271	0.047963	0.087133	-0.036372
+7.787232	0.011970	-0.002394	9.734179	0.043833	0.087533	-0.035173
+7.788206	0.033517	0.009576	9.731785	0.045965	0.089798	-0.033041
+7.789190	0.004788	0.000000	9.767695	0.047564	0.089531	-0.033708
+7.790193	0.050275	-0.002394	9.834729	0.046897	0.087799	-0.038904
+7.791206	0.081397	-0.009576	9.703056	0.047164	0.089265	-0.036905
+7.792203	0.011970	-0.004788	9.762907	0.048096	0.088599	-0.034640
+7.793204	-0.014364	-0.019152	9.829940	0.046897	0.087133	-0.032908
+7.794170	-0.028729	-0.009576	9.901762	0.046364	0.087400	-0.035972
+7.795226	-0.007182	-0.033517	9.813182	0.047031	0.087533	-0.041701
+7.796236	0.031123	-0.019152	9.777271	0.047164	0.087533	-0.038770
+7.797231	0.007182	0.009576	9.815576	0.045032	0.086067	-0.035839
+7.798215	-0.009576	0.009576	9.779666	0.045565	0.087933	-0.035706
+7.799235	-0.009576	-0.014364	9.791636	0.045965	0.088199	-0.036505
+7.800216	0.035911	0.023940	9.846699	0.047697	0.086334	-0.036106
+7.801228	-0.011970	-0.009576	9.813182	0.048363	0.088998	-0.036239
+7.802180	-0.007182	-0.007182	9.815576	0.046764	0.090064	-0.035706
+7.803168	-0.007182	0.009576	9.810788	0.043034	0.088066	-0.034107
+7.804232	-0.009576	0.028729	9.810788	0.043433	0.083936	-0.035173
+7.805232	-0.016758	-0.023940	9.777271	0.046231	0.083669	-0.037704
+7.806176	-0.007182	0.016758	9.801212	0.046897	0.087933	-0.039037
+7.807232	0.016758	-0.023940	9.762907	0.046498	0.086067	-0.039836
+7.808168	-0.014364	-0.035911	9.794030	0.046897	0.084735	-0.038504
+7.809171	0.002394	0.011970	9.810788	0.049962	0.084202	-0.037838
+7.810166	0.016758	0.021546	9.801212	0.050228	0.086467	-0.036772
+7.811160	-0.038305	-0.004788	9.832334	0.049162	0.088199	-0.037172
+7.812154	-0.007182	-0.064639	9.865851	0.046631	0.086467	-0.039170
+7.813163	-0.014364	-0.045487	9.789242	0.045565	0.086600	-0.037438
+7.814163	-0.026334	-0.007182	9.803606	0.047830	0.088332	-0.037038
+7.815174	-0.007182	0.031123	9.796424	0.048230	0.088732	-0.035440
+7.816172	-0.002394	-0.004788	9.794030	0.047963	0.089665	-0.037704
+7.817188	0.004788	-0.004788	9.817970	0.045299	0.086467	-0.037172
+7.818173	-0.007182	-0.026334	9.834729	0.043167	0.086467	-0.034907
+7.819231	0.033517	-0.045487	9.758119	0.045032	0.088599	-0.036372
+7.820202	0.028729	-0.045487	9.734179	0.046231	0.088332	-0.039436
+7.821201	-0.038305	-0.033517	9.791636	0.047697	0.086067	-0.038637
+7.822219	0.000000	-0.062245	9.791636	0.048763	0.087533	-0.033708
+7.823203	0.023940	0.019152	9.803606	0.046764	0.091263	-0.033708
+7.824245	-0.009576	-0.019152	9.750937	0.044366	0.092862	-0.036639
+7.825165	-0.002394	-0.071821	9.703056	0.044899	0.089665	-0.038637
+7.826188	-0.011970	0.004788	9.772483	0.048363	0.084735	-0.035040
+7.827199	0.071821	0.014364	9.880215	0.050495	0.083270	-0.032775
+7.828202	-0.011970	0.000000	9.837123	0.050228	0.085668	-0.036372
+7.829203	-0.007182	0.019152	9.784454	0.048763	0.089398	-0.034907
+7.830200	-0.011970	0.000000	9.736573	0.047297	0.088599	-0.033574
+7.831149	-0.035911	-0.023940	9.760513	0.046897	0.086867	-0.033308
+7.832199	-0.038305	-0.040699	9.786848	0.047164	0.087000	-0.034640
+7.833187	-0.004788	0.023940	9.827546	0.046364	0.087933	-0.035573
+7.834209	0.026334	0.000000	9.808394	0.047963	0.088466	-0.036772
+7.835149	-0.028729	-0.007182	9.861063	0.047297	0.088466	-0.038504
+7.836167	0.011970	-0.038305	9.796424	0.045698	0.088066	-0.037838
+7.837199	0.026334	-0.038305	9.779666	0.047164	0.087533	-0.039170
+7.838177	-0.021546	-0.064639	9.743755	0.043833	0.085668	-0.036639
+7.839201	0.007182	-0.031123	9.750937	0.043966	0.085401	-0.036239
+7.840199	-0.038305	-0.023940	9.750937	0.047430	0.087266	-0.037305
+7.841197	0.026334	0.000000	9.846699	0.047164	0.087266	-0.037305
+7.842205	0.028729	-0.016758	9.896974	0.048230	0.085934	-0.038904
+7.843230	0.028729	-0.021546	9.760513	0.047564	0.086334	-0.036772
+7.844231	-0.009576	-0.028729	9.844305	0.044766	0.087400	-0.037571
+7.845226	0.004788	-0.033517	9.911338	0.042234	0.088066	-0.036239
+7.846199	0.011970	-0.076609	9.844305	0.045832	0.086600	-0.040236
+7.847223	-0.033517	-0.040699	9.822758	0.047031	0.088865	-0.038770
+7.848231	-0.031123	0.009576	9.808394	0.045299	0.090997	-0.038371
+7.849233	-0.045487	-0.021546	9.779666	0.043034	0.090997	-0.034374
+7.850231	-0.026334	0.016758	9.755725	0.043433	0.087533	-0.035573
+7.851156	-0.016758	-0.052669	9.853881	0.046231	0.085135	-0.033574
+7.852230	-0.004788	-0.002394	9.853881	0.046764	0.084602	-0.033175
+7.853230	0.021546	-0.004788	9.760513	0.046631	0.086201	-0.036239
+7.854235	0.033517	-0.007182	9.719814	0.046098	0.088332	-0.039170
+7.855202	0.021546	0.011970	9.822758	0.046098	0.090064	-0.037704
+7.856183	0.033517	-0.007182	9.839517	0.046764	0.089398	-0.035573
+7.857173	-0.009576	0.007182	9.755725	0.048230	0.086600	-0.032775
+7.858173	0.016758	0.026334	9.887397	0.046631	0.085801	-0.034640
+7.859230	0.009576	-0.043093	9.863457	0.047297	0.086600	-0.038637
+7.860202	0.035911	0.031123	9.762907	0.047830	0.089531	-0.040636
+7.861164	0.019152	-0.067033	9.822758	0.048896	0.089665	-0.039170
+7.862232	0.011970	-0.062245	9.892186	0.049562	0.088865	-0.034773
+7.863225	0.064639	-0.076609	9.940066	0.047164	0.087933	-0.034640
+7.864230	0.026334	-0.028729	9.837123	0.046364	0.088199	-0.034374
+7.865231	0.004788	-0.002394	9.753331	0.045432	0.087533	-0.036106
+7.866232	0.004788	0.016758	9.762907	0.047963	0.087000	-0.036372
+7.867202	0.026334	0.016758	9.743755	0.048763	0.086067	-0.037172
+7.868179	0.055063	0.026334	9.832334	0.047164	0.089665	-0.037172
+7.869182	0.045487	-0.035911	9.820364	0.047430	0.088732	-0.035972
+7.870184	0.026334	-0.011970	9.832334	0.049562	0.085002	-0.035440
+7.871169	0.083792	0.043093	9.798818	0.048629	0.084868	-0.035040
+7.872170	0.033517	0.023940	9.829940	0.047430	0.087933	-0.035573
+7.873204	0.023940	0.000000	9.870639	0.047430	0.091530	-0.039836
+7.874204	-0.007182	-0.009576	9.741361	0.047297	0.091930	-0.036772
+7.875203	0.007182	-0.009576	9.758119	0.047164	0.089798	-0.035839
+7.876204	0.002394	-0.033517	9.839517	0.046764	0.086201	-0.036639
+7.877203	-0.007182	0.040699	9.858669	0.045698	0.084602	-0.035440
+7.878197	-0.002394	0.019152	9.844305	0.045565	0.089665	-0.037038
+7.879201	0.014364	0.000000	9.829940	0.048896	0.089132	-0.037438
+7.880178	0.016758	-0.007182	9.736573	0.049429	0.086334	-0.035972
+7.881177	0.011970	-0.007182	9.772483	0.047564	0.088066	-0.034907
+7.882232	0.011970	0.011970	9.853881	0.048496	0.089665	-0.036772
+7.883232	-0.026334	-0.004788	9.808394	0.049429	0.089398	-0.038504
+7.884230	0.026334	-0.019152	9.798818	0.046631	0.087666	-0.036239
+7.885231	0.021546	-0.045487	9.810788	0.046098	0.086467	-0.036505
+7.886194	-0.002394	-0.059851	9.849093	0.047697	0.086201	-0.037838
+7.887230	-0.021546	0.038305	9.801212	0.049429	0.086067	-0.036639
+7.888232	-0.021546	-0.031123	9.832334	0.048763	0.087533	-0.039037
+7.889240	0.035911	-0.023940	9.750937	0.044233	0.090198	-0.036772
+7.890206	-0.009576	0.026334	9.822758	0.044499	0.087133	-0.037571
+7.891203	-0.007182	-0.002394	9.832334	0.046631	0.087666	-0.039570
+7.892233	0.014364	-0.021546	9.839517	0.048230	0.087133	-0.038770
+7.893226	0.057457	-0.043093	9.779666	0.046231	0.084335	-0.039436
+7.894232	0.052669	0.000000	9.755725	0.044632	0.084735	-0.038504
+7.895230	0.021546	-0.038305	9.817970	0.044899	0.087000	-0.036106
+7.896172	0.007182	-0.067033	9.817970	0.048629	0.088732	-0.031576
+7.897175	0.011970	-0.011970	9.789242	0.048896	0.087933	-0.034773
+7.898224	0.052669	0.014364	9.817970	0.046764	0.088599	-0.036639
+7.899231	0.000000	-0.019152	9.820364	0.046098	0.087666	-0.034773
+7.900224	-0.004788	-0.004788	9.856275	0.045698	0.088998	-0.036905
+7.901224	0.035911	-0.016758	9.753331	0.045032	0.088066	-0.038371
+7.902234	0.045487	-0.040699	9.801212	0.045565	0.087933	-0.035706
+7.903232	0.038305	-0.019152	9.834729	0.046897	0.088332	-0.033175
+7.904230	0.050275	0.000000	9.889792	0.047297	0.089132	-0.035839
+7.905231	0.019152	0.002394	9.863457	0.046364	0.089665	-0.037305
+7.906234	0.059851	0.009576	9.832334	0.045165	0.089265	-0.035306
+7.907230	0.028729	0.045487	9.753331	0.045299	0.087400	-0.035839
+7.908229	-0.057457	-0.021546	9.748543	0.047564	0.083536	-0.036639
+7.909231	0.026334	0.016758	9.743755	0.050628	0.083403	-0.035306
+7.910191	0.002394	-0.033517	9.755725	0.048896	0.087266	-0.034240
+7.911255	-0.011970	-0.016758	9.782060	0.049562	0.089531	-0.035573
+7.912232	0.050275	-0.021546	9.846699	0.049429	0.087533	-0.035573
+7.913233	0.095762	-0.004788	9.817970	0.045032	0.086334	-0.038371
+7.914234	0.069427	0.007182	9.896974	0.044366	0.086734	-0.036772
+7.915230	0.009576	0.062245	9.825152	0.045698	0.087799	-0.036372
+7.916172	-0.002394	0.016758	9.760513	0.047297	0.086734	-0.036772
+7.917153	0.002394	-0.055063	9.750937	0.048496	0.087933	-0.037305
+7.918150	0.000000	0.002394	9.731785	0.047164	0.088998	-0.037172
+7.919154	0.043093	0.016758	9.849093	0.046897	0.087133	-0.035706
+7.920230	0.033517	-0.028729	9.770089	0.048496	0.087000	-0.036372
+7.921165	-0.047881	-0.004788	9.772483	0.048896	0.086867	-0.037704
+7.922242	-0.021546	0.035911	9.722208	0.047430	0.086334	-0.036772
+7.923230	-0.016758	-0.055063	9.844305	0.046498	0.087799	-0.035440
+7.924230	0.079003	-0.011970	9.820364	0.046764	0.087666	-0.035972
+7.925231	0.023940	0.019152	9.834729	0.046897	0.088066	-0.035972
+7.926234	0.002394	0.002394	9.760513	0.047830	0.088466	-0.036905
+7.927232	0.011970	-0.040699	9.782060	0.048496	0.090064	-0.038237
+7.928228	-0.004788	0.014364	9.736573	0.047963	0.087799	-0.039969
+7.929227	0.016758	0.043093	9.853881	0.047297	0.087799	-0.036106
+7.930232	0.009576	0.031123	9.806000	0.044366	0.085534	-0.034640
+7.931163	-0.023940	0.050275	9.784454	0.043966	0.087666	-0.036639
+7.932177	0.007182	0.007182	9.789242	0.044766	0.088332	-0.035040
+7.933230	-0.040699	-0.043093	9.834729	0.045165	0.087666	-0.034773
+7.934233	-0.021546	-0.028729	9.784454	0.043700	0.086467	-0.035839
+7.935231	0.026334	-0.014364	9.813182	0.044100	0.087400	-0.036106
+7.936225	0.031123	-0.023940	9.746149	0.049029	0.086600	-0.035040
+7.937230	-0.009576	0.031123	9.810788	0.050495	0.088732	-0.034640
+7.938231	-0.007182	0.033517	9.770089	0.046764	0.089531	-0.034374
+7.939230	0.043093	0.009576	9.806000	0.044233	0.088332	-0.035173
+7.940201	0.026334	-0.035911	9.885003	0.047564	0.086867	-0.036106
+7.941199	0.033517	-0.023940	9.868245	0.048363	0.086334	-0.036505
+7.942224	0.069427	-0.043093	9.829940	0.047830	0.086867	-0.034907
+7.943231	0.067033	-0.038305	9.820364	0.048363	0.088732	-0.035040
+7.944225	0.055063	-0.002394	9.801212	0.046364	0.087000	-0.037838
+7.945206	0.023940	-0.004788	9.820364	0.045032	0.086734	-0.035573
+7.946174	0.016758	0.019152	9.750937	0.046897	0.089531	-0.037438
+7.947169	0.026334	0.021546	9.798818	0.048629	0.090198	-0.037971
+7.948160	-0.002394	-0.043093	9.808394	0.045832	0.088199	-0.037038
+7.949198	0.083792	-0.038305	9.770089	0.045299	0.088332	-0.036905
+7.950155	0.035911	0.007182	9.796424	0.047297	0.088732	-0.033308
+7.951197	0.016758	0.002394	9.885003	0.047830	0.088199	-0.033308
+7.952198	-0.004788	-0.019152	9.796424	0.048363	0.087799	-0.034507
+7.953208	-0.016758	0.009576	9.827546	0.047430	0.088332	-0.034907
+7.954202	-0.031123	0.002394	9.846699	0.046231	0.088998	-0.038770
+7.955226	0.002394	-0.007182	9.794030	0.047564	0.088865	-0.037038
+7.956230	0.002394	-0.040699	9.743755	0.046897	0.088599	-0.036905
+7.957229	0.019152	0.009576	9.703056	0.045698	0.087666	-0.034640
+7.958231	0.033517	0.028729	9.767695	0.047697	0.087933	-0.037305
+7.959200	0.076609	-0.026334	9.837123	0.049695	0.088599	-0.035573
+7.960186	0.055063	-0.040699	9.870639	0.050894	0.089665	-0.037038
+7.961186	0.031123	-0.031123	9.846699	0.047963	0.088732	-0.036505
+7.962194	0.038305	0.014364	9.798818	0.048363	0.088466	-0.037305
+7.963186	0.035911	0.000000	9.767695	0.048230	0.088998	-0.037971
+7.964185	0.026334	-0.011970	9.801212	0.045432	0.087933	-0.037438
+7.965198	0.050275	-0.033517	9.887397	0.045698	0.086067	-0.036772
+7.966167	0.064639	-0.052669	9.911338	0.046897	0.088199	-0.037305
+7.967172	0.035911	-0.062245	9.911338	0.047430	0.089398	-0.033974
+7.968203	0.016758	-0.028729	9.870639	0.047297	0.087400	-0.030643
+7.969211	0.038305	0.014364	9.798818	0.046364	0.085135	-0.034640
+7.970230	-0.026334	0.040699	9.755725	0.043567	0.086600	-0.037172
+7.971223	-0.033517	0.014364	9.738967	0.043567	0.085268	-0.037438
+7.972236	-0.002394	-0.035911	9.774877	0.045698	0.085534	-0.035706
+7.973229	0.028729	0.040699	9.868245	0.048629	0.087133	-0.036106
+7.974224	0.000000	0.026334	9.789242	0.048896	0.088865	-0.034240
+7.975170	-0.004788	0.007182	9.801212	0.049962	0.090464	-0.034907
+7.976153	0.035911	-0.023940	9.803606	0.048629	0.089132	-0.036239
+7.977135	0.021546	-0.002394	9.770089	0.046897	0.089398	-0.037038
+7.978143	0.031123	-0.011970	9.865851	0.044899	0.089265	-0.038637
+7.979147	0.035911	-0.023940	9.837123	0.045565	0.089132	-0.041168
+7.980152	0.038305	0.014364	9.844305	0.049962	0.087133	-0.038904
+7.981152	0.000000	-0.014364	9.928096	0.053426	0.086600	-0.032775
+7.982147	-0.026334	-0.071821	9.906550	0.050228	0.090464	-0.032508
+7.983140	0.028729	-0.026334	9.839517	0.044632	0.090464	-0.037038
+7.984145	-0.009576	0.004788	9.844305	0.044632	0.087666	-0.039170
+7.985138	0.014364	-0.019152	9.875427	0.049296	0.087400	-0.036905
+7.986145	-0.014364	0.000000	9.846699	0.050894	0.089398	-0.033841
+7.987151	0.000000	-0.009576	9.863457	0.047297	0.091530	-0.037038
+7.988151	0.016758	-0.021546	9.885003	0.046764	0.089531	-0.040902
+7.989151	0.057457	-0.014364	9.858669	0.046897	0.085534	-0.036372
+7.990145	-0.009576	-0.028729	9.832334	0.047297	0.085668	-0.035306
+7.991137	0.002394	-0.033517	9.853881	0.047697	0.087266	-0.037305
+7.992168	0.057457	-0.031123	9.810788	0.046897	0.087000	-0.036772
+7.993210	0.016758	0.011970	9.825152	0.045698	0.085002	-0.037038
+7.994162	0.031123	0.004788	9.868245	0.044366	0.084735	-0.040502
+7.995162	0.026334	-0.009576	9.832334	0.045165	0.087533	-0.040236
+7.996160	-0.055063	-0.038305	9.868245	0.047564	0.088332	-0.039037
+7.997181	-0.009576	-0.007182	9.779666	0.047963	0.086600	-0.035839
+7.998182	0.009576	-0.031123	9.853881	0.048096	0.086334	-0.034507
+7.999180	-0.002394	-0.040699	9.827546	0.049296	0.083669	-0.035972
+8.000173	0.004788	-0.009576	9.779666	0.048096	0.083936	-0.039170
+8.001132	0.019152	-0.014364	9.765301	0.047164	0.086867	-0.036772
+8.002178	-0.016758	-0.011970	9.808394	0.047430	0.087266	-0.036239
+8.003209	0.031123	0.019152	9.815576	0.047697	0.087266	-0.038237
+8.004183	0.007182	0.031123	9.820364	0.047963	0.089931	-0.037438
+8.005212	-0.014364	-0.031123	9.822758	0.047697	0.089798	-0.036372
+8.006163	0.035911	0.009576	9.856275	0.046764	0.088865	-0.038770
+8.007163	0.007182	0.033517	9.815576	0.046231	0.086467	-0.036905
+8.008179	0.071821	0.011970	9.858669	0.045965	0.086600	-0.036372
+8.009148	0.050275	-0.059851	9.853881	0.046231	0.088732	-0.037172
+8.010178	-0.023940	-0.009576	9.904156	0.045832	0.088865	-0.039703
+8.011182	-0.007182	-0.009576	9.837123	0.044632	0.087533	-0.040502
+8.012172	0.035911	-0.021546	9.810788	0.045565	0.088066	-0.037172
+8.013173	0.023940	0.002394	9.767695	0.043300	0.085268	-0.036239
+8.014177	-0.043093	-0.028729	9.760513	0.044499	0.088466	-0.037438
+8.015207	0.004788	-0.028729	9.832334	0.045032	0.091930	-0.035972
+8.016182	-0.023940	-0.023940	9.896974	0.046098	0.088865	-0.039436
+8.017158	-0.038305	-0.055063	9.808394	0.046631	0.087666	-0.039303
+8.018204	-0.009576	-0.007182	9.798818	0.047830	0.087933	-0.037438
+8.019150	0.021546	-0.009576	9.810788	0.047830	0.088066	-0.039170
+8.020223	-0.038305	-0.050275	9.841911	0.048629	0.090464	-0.041035
+8.021221	-0.019152	0.023940	9.856275	0.048230	0.089132	-0.038637
+8.022219	0.031123	0.002394	9.829940	0.047564	0.087799	-0.036505
+8.023224	0.035911	-0.016758	9.822758	0.047697	0.088865	-0.038237
+8.024224	0.064639	0.064639	9.829940	0.048363	0.089398	-0.034907
+8.025221	0.071821	0.028729	9.779666	0.049162	0.088332	-0.034907
+8.026223	-0.004788	-0.021546	9.817970	0.049828	0.087400	-0.033974
+8.027221	-0.055063	-0.031123	9.767695	0.048629	0.087933	-0.035839
+8.028211	-0.026334	-0.023940	9.834729	0.047297	0.087666	-0.040236
+8.029201	-0.033517	-0.026334	9.777271	0.048096	0.087666	-0.040502
+8.030183	0.019152	-0.014364	9.717420	0.048896	0.085668	-0.037704
+8.031180	0.045487	-0.057457	9.820364	0.047031	0.086201	-0.033974
+8.032182	0.009576	-0.019152	9.858669	0.043433	0.087133	-0.033708
+8.033224	0.004788	-0.004788	9.789242	0.045432	0.086600	-0.034640
+8.034224	0.002394	-0.016758	9.755725	0.047830	0.086734	-0.039703
+8.035217	0.000000	0.009576	9.789242	0.049029	0.084735	-0.037571
+8.036220	-0.021546	0.033517	9.789242	0.046897	0.087933	-0.035040
+8.037222	-0.023940	0.038305	9.832334	0.047564	0.087666	-0.034240
+8.038223	0.026334	0.004788	9.880215	0.046897	0.087400	-0.038504
+8.039204	0.007182	0.002394	9.868245	0.044366	0.088732	-0.039303
+8.040156	0.000000	-0.007182	9.863457	0.044366	0.088066	-0.037305
+8.041161	-0.023940	-0.023940	9.829940	0.046098	0.086334	-0.038237
+8.042207	0.009576	-0.021546	9.829940	0.048230	0.087000	-0.037438
+8.043160	0.038305	-0.016758	9.810788	0.048096	0.085801	-0.035972
+8.044157	-0.007182	0.021546	9.722208	0.045165	0.086201	-0.035706
+8.045173	-0.026334	-0.047881	9.731785	0.044100	0.086600	-0.034240
+8.046177	0.009576	0.026334	9.803606	0.045165	0.089132	-0.037305
+8.047222	-0.040699	-0.009576	9.880215	0.047297	0.087799	-0.040369
+8.048222	0.055063	-0.038305	9.839517	0.048496	0.084469	-0.038770
+8.049221	0.062245	-0.028729	9.770089	0.047430	0.084868	-0.035839
+8.050184	-0.004788	-0.016758	9.813182	0.046231	0.088199	-0.034374
+8.051171	-0.057457	-0.002394	9.782060	0.046897	0.086467	-0.037571
+8.052209	0.007182	-0.023940	9.724603	0.047430	0.086734	-0.037172
+8.053206	0.038305	-0.043093	9.772483	0.047830	0.088332	-0.035706
+8.054180	-0.016758	-0.004788	9.731785	0.048763	0.087666	-0.036639
+8.055200	0.067033	-0.009576	9.762907	0.047430	0.087266	-0.034773
+8.056156	0.038305	0.004788	9.808394	0.048096	0.086067	-0.035040
+8.057162	-0.004788	0.007182	9.889792	0.048096	0.088466	-0.036505
+8.058179	0.014364	-0.016758	9.844305	0.046364	0.089398	-0.039436
+8.059173	0.052669	0.038305	9.712632	0.045698	0.089531	-0.037305
+8.060204	0.023940	0.007182	9.719814	0.047031	0.089265	-0.034907
+8.061220	0.033517	-0.016758	9.767695	0.048896	0.091930	-0.035839
+8.062223	0.014364	-0.093368	9.801212	0.047564	0.088865	-0.035972
+8.063179	0.002394	-0.038305	9.794030	0.045032	0.087533	-0.039170
+8.064184	-0.023940	0.038305	9.839517	0.043433	0.088599	-0.039969
+8.065207	-0.019152	0.045487	9.856275	0.046098	0.088865	-0.038637
+8.066160	-0.031123	-0.009576	9.906550	0.047564	0.088998	-0.036639
+8.067223	0.019152	0.000000	9.851487	0.048629	0.087533	-0.035040
+8.068150	0.059851	0.000000	9.841911	0.047297	0.087533	-0.033708
+8.069172	0.052669	0.000000	9.753331	0.045565	0.091263	-0.033308
+8.070177	0.002394	-0.002394	9.707844	0.047031	0.090464	-0.035839
+8.071223	0.009576	0.019152	9.794030	0.045432	0.088865	-0.032642
+8.072222	0.026334	0.021546	9.887397	0.045832	0.084868	-0.032508
+8.073224	-0.026334	0.014364	9.868245	0.046364	0.082603	-0.034907
+8.074225	-0.050275	-0.014364	9.827546	0.046764	0.086067	-0.036372
+8.075223	-0.014364	-0.004788	9.774877	0.046631	0.087533	-0.040502
+8.076193	0.016758	-0.002394	9.731785	0.045698	0.086467	-0.037838
+8.077193	0.002394	0.023940	9.832334	0.046364	0.085934	-0.032908
+8.078219	-0.011970	-0.011970	9.825152	0.049029	0.087933	-0.034107
+8.079221	-0.033517	0.000000	9.810788	0.048363	0.088599	-0.036905
+8.080221	-0.031123	0.021546	9.810788	0.047430	0.087666	-0.035972
+8.081181	0.004788	-0.007182	9.782060	0.046631	0.089665	-0.037704
+8.082180	0.047881	-0.004788	9.796424	0.047031	0.091530	-0.042101
+8.083218	0.043093	-0.004788	9.753331	0.046098	0.088732	-0.040769
+8.084180	0.016758	-0.016758	9.734179	0.046098	0.087400	-0.038637
+8.085229	0.026334	0.000000	9.707844	0.046498	0.089798	-0.034240
+8.086224	0.014364	0.035911	9.791636	0.046897	0.090064	-0.035040
+8.087213	0.021546	-0.002394	9.784454	0.046231	0.088865	-0.040769
+8.088240	0.043093	0.035911	9.770089	0.047297	0.088332	-0.039436
+8.089178	0.067033	0.014364	9.789242	0.047031	0.087400	-0.036905
+8.090136	0.038305	0.014364	9.813182	0.048763	0.088599	-0.035306
+8.091214	0.035911	-0.014364	9.803606	0.048363	0.088998	-0.034640
+8.092220	0.026334	-0.016758	9.803606	0.051028	0.088066	-0.033974
+8.093220	0.002394	-0.064639	9.796424	0.049296	0.090064	-0.036505
+8.094178	-0.004788	0.004788	9.870639	0.047297	0.088066	-0.038104
+8.095214	0.000000	0.016758	9.832334	0.045165	0.085002	-0.038904
+8.096214	0.007182	-0.019152	9.746149	0.045432	0.086600	-0.037038
+8.097218	0.026334	-0.011970	9.784454	0.047430	0.088332	-0.033841
+8.098221	0.014364	-0.031123	9.767695	0.047297	0.087666	-0.034773
+8.099197	-0.047881	-0.045487	9.839517	0.047031	0.086334	-0.038904
+8.100204	0.000000	-0.026334	9.779666	0.048363	0.088732	-0.037438
+8.101179	0.004788	-0.009576	9.829940	0.046231	0.089931	-0.036239
+8.102146	0.019152	0.028729	9.774877	0.044100	0.089132	-0.036639
+8.103221	-0.047881	0.004788	9.808394	0.045165	0.085801	-0.037571
+8.104216	-0.033517	0.067033	9.817970	0.045032	0.085401	-0.034507
+8.105203	-0.086186	0.035911	9.829940	0.043966	0.086067	-0.031842
+8.106223	-0.040699	-0.035911	9.815576	0.046897	0.087933	-0.034240
+8.107221	0.004788	-0.026334	9.856275	0.047564	0.089132	-0.040369
+8.108151	-0.014364	0.026334	9.806000	0.044366	0.088998	-0.040769
+8.109160	-0.004788	0.035911	9.817970	0.044366	0.087400	-0.039969
+8.110208	-0.009576	-0.011970	9.794030	0.046364	0.088732	-0.037838
+8.111208	-0.014364	-0.014364	9.832334	0.048629	0.089931	-0.036505
+8.112201	-0.026334	0.009576	9.858669	0.047430	0.087933	-0.037971
+8.113161	0.004788	0.009576	9.825152	0.045165	0.085401	-0.036239
+8.114180	0.004788	-0.007182	9.856275	0.044366	0.085934	-0.035573
+8.115183	0.038305	-0.064639	9.853881	0.045032	0.087000	-0.036639
+8.116220	0.043093	-0.055063	9.813182	0.044899	0.087000	-0.038371
+8.117216	0.045487	-0.043093	9.868245	0.047564	0.087000	-0.035573
+8.118159	-0.002394	-0.045487	9.865851	0.048230	0.088732	-0.034507
+8.119177	0.009576	-0.031123	9.703056	0.048763	0.089531	-0.035839
+8.120218	0.021546	0.009576	9.703056	0.047830	0.087400	-0.036239
+8.121185	0.045487	0.000000	9.772483	0.047031	0.087000	-0.037038
+8.122206	0.016758	-0.021546	9.784454	0.044100	0.087266	-0.037704
+8.123177	-0.026334	-0.004788	9.832334	0.045832	0.089132	-0.035306
+8.124206	-0.040699	-0.009576	9.825152	0.047830	0.090331	-0.035440
+8.125155	0.028729	0.002394	9.817970	0.049962	0.089931	-0.034907
+8.126180	0.057457	-0.031123	9.748543	0.048230	0.089798	-0.033574
+8.127179	0.059851	-0.009576	9.856275	0.046498	0.086600	-0.032908
+8.128220	0.014364	-0.002394	9.861063	0.046231	0.086067	-0.033708
+8.129220	-0.014364	-0.071821	9.789242	0.047564	0.088066	-0.035306
+8.130223	-0.026334	0.021546	9.786848	0.049162	0.088199	-0.039170
+8.131221	-0.038305	0.002394	9.760513	0.047164	0.087266	-0.041835
+8.132164	-0.016758	-0.026334	9.710238	0.048096	0.085668	-0.037838
+8.133172	-0.031123	-0.059851	9.743755	0.047830	0.085801	-0.034107
+8.134208	0.019152	-0.019152	9.774877	0.046098	0.087666	-0.032508
+8.135169	0.019152	-0.004788	9.801212	0.044366	0.088599	-0.032508
+8.136172	0.011970	-0.052669	9.770089	0.044499	0.088332	-0.032109
+8.137164	-0.071821	0.016758	9.786848	0.045965	0.086334	-0.036772
+8.138133	-0.021546	-0.007182	9.772483	0.044233	0.088466	-0.038904
+8.139171	-0.028729	0.000000	9.794030	0.045299	0.089398	-0.038904
+8.140171	-0.035911	0.011970	9.846699	0.048629	0.088732	-0.035573
+8.141194	-0.011970	-0.019152	9.808394	0.050894	0.087266	-0.034240
+8.142173	0.004788	-0.019152	9.789242	0.049562	0.086067	-0.035440
+8.143216	0.052669	0.026334	9.806000	0.047830	0.086467	-0.035573
+8.144219	0.047881	0.043093	9.789242	0.048363	0.088066	-0.033708
+8.145222	0.014364	0.028729	9.820364	0.048496	0.088199	-0.032642
+8.146222	-0.014364	-0.057457	9.758119	0.047697	0.087133	-0.033041
+8.147216	0.043093	-0.021546	9.767695	0.046631	0.083270	-0.037438
+8.148212	0.004788	-0.002394	9.789242	0.046897	0.086201	-0.038371
+8.149222	-0.002394	0.000000	9.806000	0.050095	0.088599	-0.039170
+8.150224	-0.004788	-0.052669	9.770089	0.049562	0.088732	-0.034773
+8.151220	-0.035911	-0.023940	9.861063	0.047164	0.088066	-0.033441
+8.152222	-0.014364	-0.002394	9.837123	0.044632	0.083936	-0.036772
+8.153221	0.050275	0.038305	9.798818	0.045965	0.086067	-0.036372
+8.154222	-0.009576	0.028729	9.858669	0.045032	0.087400	-0.036772
+8.155209	-0.011970	0.016758	9.834729	0.047164	0.087133	-0.039170
+8.156217	-0.016758	0.011970	9.829940	0.049962	0.088865	-0.040636
+8.157218	0.014364	0.028729	9.746149	0.049828	0.088332	-0.038637
+8.158204	0.021546	0.040699	9.755725	0.046631	0.087266	-0.038237
+8.159193	0.028729	0.028729	9.829940	0.046764	0.087000	-0.037038
+8.160171	0.026334	-0.047881	9.772483	0.047031	0.089132	-0.034773
+8.161172	0.028729	-0.047881	9.796424	0.045565	0.090730	-0.034773
+8.162222	0.040699	0.043093	9.798818	0.045299	0.088865	-0.035040
+8.163220	-0.002394	-0.002394	9.681510	0.045299	0.086067	-0.037438
+8.164212	0.000000	-0.043093	9.750937	0.047164	0.085934	-0.038504
+8.165218	0.011970	0.031123	9.803606	0.047963	0.086867	-0.038104
+8.166220	0.035911	-0.011970	9.834729	0.046764	0.088998	-0.038904
+8.167220	-0.007182	-0.019152	9.817970	0.047830	0.088599	-0.037971
+8.168162	0.004788	0.023940	9.806000	0.047031	0.087400	-0.035839
+8.169180	0.000000	-0.016758	9.827546	0.047297	0.087666	-0.037704
+8.170224	0.016758	0.016758	9.849093	0.047564	0.087000	-0.039836
+8.171220	0.035911	-0.064639	9.796424	0.047963	0.089265	-0.040502
+8.172219	0.002394	0.028729	9.820364	0.047430	0.090464	-0.036639
+8.173216	0.028729	0.021546	9.815576	0.047430	0.089798	-0.033041
+8.174223	0.021546	-0.009576	9.786848	0.048096	0.087666	-0.032908
+8.175220	0.000000	-0.021546	9.808394	0.048496	0.085401	-0.035306
+8.176221	0.000000	-0.026334	9.815576	0.047031	0.085534	-0.037438
+8.177221	-0.057457	-0.031123	9.808394	0.045832	0.088599	-0.035839
+8.178222	-0.011970	0.028729	9.810788	0.047031	0.090331	-0.031043
+8.179196	0.031123	0.011970	9.810788	0.047430	0.089665	-0.035706
+8.180237	-0.045487	0.007182	9.868245	0.047164	0.088732	-0.038770
+8.181222	-0.023940	0.033517	9.856275	0.045965	0.086600	-0.038237
+8.182151	-0.007182	-0.004788	9.853881	0.046631	0.086067	-0.038504
+8.183222	0.045487	-0.011970	9.837123	0.047297	0.087933	-0.037971
+8.184222	-0.033517	-0.016758	9.760513	0.048363	0.087133	-0.034374
+8.185175	0.052669	-0.007182	9.834729	0.049296	0.087533	-0.035839
+8.186153	0.043093	0.028729	9.832334	0.049695	0.087400	-0.037038
+8.187154	0.038305	0.019152	9.870639	0.049029	0.090730	-0.036106
+8.188154	0.057457	-0.028729	9.789242	0.046364	0.091130	-0.038504
+8.189155	0.033517	0.011970	9.767695	0.044766	0.087400	-0.037438
+8.190157	-0.016758	-0.026334	9.796424	0.046764	0.086467	-0.037172
+8.191147	-0.033517	-0.009576	9.841911	0.047164	0.087400	-0.037838
+8.192236	-0.062245	-0.050275	9.777271	0.046897	0.085534	-0.035839
+8.193128	0.033517	-0.019152	9.784454	0.044632	0.086600	-0.037038
+8.194122	0.038305	0.016758	9.786848	0.046764	0.087666	-0.038237
+8.195121	-0.002394	0.004788	9.722208	0.048763	0.088466	-0.035839
+8.196218	0.009576	-0.002394	9.887397	0.050628	0.087533	-0.038104
+8.197178	0.033517	0.043093	9.853881	0.047963	0.088332	-0.035306
+8.198161	0.050275	0.043093	9.815576	0.046231	0.086867	-0.032109
+8.199165	-0.023940	0.000000	9.784454	0.047963	0.085135	-0.034107
+8.200152	-0.023940	0.007182	9.796424	0.046631	0.083802	-0.034773
+8.201156	0.016758	0.014364	9.837123	0.047830	0.087933	-0.036905
+8.202153	0.050275	0.014364	9.772483	0.049695	0.088998	-0.036905
+8.203160	-0.007182	0.019152	9.849093	0.045299	0.087799	-0.035839
+8.204201	-0.038305	0.016758	9.803606	0.044766	0.088466	-0.036905
+8.205160	-0.023940	-0.016758	9.806000	0.046098	0.087933	-0.036239
+8.206164	-0.004788	0.002394	9.873033	0.046364	0.087400	-0.034773
+8.207153	-0.040699	-0.004788	9.832334	0.049029	0.088066	-0.035440
+8.208140	0.021546	-0.031123	9.908944	0.048763	0.086467	-0.035706
+8.209169	0.088580	-0.026334	9.798818	0.049029	0.088599	-0.036772
+8.210177	0.019152	-0.043093	9.695874	0.048096	0.089265	-0.038770
+8.211220	-0.035911	0.011970	9.815576	0.045432	0.088199	-0.037838
+8.212219	-0.019152	-0.019152	9.887397	0.045565	0.086467	-0.038637
+8.213224	-0.050275	-0.009576	9.798818	0.045299	0.085002	-0.038371
+8.214193	-0.031123	0.007182	9.762907	0.046498	0.086600	-0.036905
+8.215157	0.043093	0.035911	9.746149	0.047164	0.087133	-0.035440
+8.216218	0.026334	0.002394	9.815576	0.046631	0.087400	-0.034640
+8.217222	-0.028729	-0.031123	9.796424	0.049029	0.086734	-0.035573
+8.218159	-0.007182	0.019152	9.724603	0.048230	0.087133	-0.036106
+8.219223	-0.014364	0.059851	9.834729	0.045299	0.088599	-0.036772
+8.220225	0.033517	0.090974	9.813182	0.046364	0.090064	-0.036372
+8.221222	0.016758	0.043093	9.796424	0.048096	0.088332	-0.035040
+8.222224	0.043093	0.023940	9.712632	0.047830	0.085934	-0.035972
+8.223206	0.011970	-0.004788	9.789242	0.045165	0.087266	-0.035040
+8.224194	-0.014364	-0.047881	9.834729	0.044499	0.087933	-0.032642
+8.225141	-0.040699	-0.019152	9.820364	0.047564	0.089398	-0.036772
+8.226165	-0.011970	-0.002394	9.774877	0.050894	0.091663	-0.038637
+8.227175	-0.007182	0.026334	9.820364	0.048496	0.091530	-0.036106
+8.228171	0.009576	-0.023940	9.784454	0.048230	0.090331	-0.033974
+8.229222	0.067033	-0.019152	9.767695	0.049296	0.088599	-0.034640
+8.230225	0.028729	0.016758	9.827546	0.049029	0.087533	-0.035972
+8.231159	0.019152	-0.026334	9.762907	0.047297	0.085668	-0.037704
+8.232162	0.026334	-0.011970	9.772483	0.047430	0.087533	-0.038104
+8.233224	0.009576	0.014364	9.774877	0.048363	0.089665	-0.038371
+8.234161	-0.055063	0.009576	9.784454	0.049029	0.086600	-0.036505
+8.235160	0.011970	-0.052669	9.712632	0.048096	0.086600	-0.033841
+8.236206	0.043093	-0.002394	9.791636	0.046764	0.087666	-0.035173
+8.237243	0.009576	-0.038305	9.801212	0.045299	0.087933	-0.035573
+8.238168	-0.002394	-0.009576	9.810788	0.046897	0.086201	-0.038104
+8.239221	-0.019152	0.007182	9.767695	0.045698	0.086600	-0.037571
+8.240222	0.021546	-0.019152	9.827546	0.043034	0.086600	-0.036106
+8.241222	0.002394	-0.028729	9.772483	0.045165	0.087000	-0.035573
+8.242216	-0.004788	-0.040699	9.741361	0.047031	0.088199	-0.036905
+8.243145	-0.033517	-0.043093	9.726997	0.046764	0.088066	-0.036639
+8.244219	-0.023940	-0.007182	9.827546	0.043433	0.088332	-0.035573
+8.245221	-0.009576	0.021546	9.870639	0.045032	0.084868	-0.035440
+8.246234	0.000000	-0.009576	9.762907	0.049695	0.084868	-0.036239
+8.247199	-0.045487	-0.014364	9.710238	0.048763	0.089265	-0.034374
+8.248219	0.019152	0.043093	9.801212	0.045565	0.088998	-0.032109
+8.249184	0.033517	0.021546	9.858669	0.046764	0.086734	-0.034907
+8.250157	0.028729	-0.009576	9.841911	0.048230	0.086867	-0.038637
+8.251160	-0.014364	-0.009576	9.863457	0.047564	0.088599	-0.035173
+8.252220	-0.040699	-0.045487	9.777271	0.045965	0.088332	-0.033708
+8.253221	0.007182	-0.019152	9.789242	0.044766	0.088199	-0.034107
+8.254223	-0.007182	0.007182	9.772483	0.045032	0.089398	-0.033708
+8.255203	0.011970	0.016758	9.779666	0.043034	0.090331	-0.036505
+8.256227	0.035911	-0.007182	9.822758	0.045432	0.091263	-0.035040
+8.257174	0.071821	0.007182	9.782060	0.046897	0.089265	-0.035173
+8.258225	0.033517	0.004788	9.829940	0.047963	0.088332	-0.035839
+8.259183	0.023940	-0.028729	9.815576	0.049029	0.088199	-0.036772
+8.260207	0.088580	-0.047881	9.729391	0.047697	0.088199	-0.039836
+8.261182	0.016758	0.026334	9.729391	0.046231	0.088865	-0.037571
+8.262223	-0.011970	0.000000	9.801212	0.044899	0.089798	-0.038237
+8.263218	-0.055063	-0.059851	9.863457	0.045565	0.088865	-0.039170
+8.264216	-0.045487	-0.016758	9.815576	0.048230	0.085801	-0.038504
+8.265223	-0.011970	0.035911	9.803606	0.048496	0.086067	-0.038371
+8.266163	-0.004788	0.021546	9.767695	0.048896	0.087266	-0.037305
+8.267176	-0.035911	0.000000	9.827546	0.047830	0.087533	-0.035839
+8.268219	0.023940	-0.011970	9.846699	0.046231	0.085934	-0.035173
+8.269205	0.028729	-0.021546	9.863457	0.046764	0.087266	-0.036772
+8.270222	-0.019152	0.007182	9.803606	0.046498	0.091663	-0.039969
+8.271220	0.009576	-0.004788	9.760513	0.047963	0.089132	-0.041302
+8.272219	0.026334	-0.002394	9.851487	0.047564	0.088466	-0.037704
+8.273225	-0.004788	-0.033517	9.817970	0.044366	0.088732	-0.032508
+8.274216	-0.023940	0.002394	9.777271	0.046231	0.090331	-0.033041
+8.275222	-0.052669	0.033517	9.868245	0.047963	0.090464	-0.035173
+8.276210	-0.031123	0.038305	9.815576	0.046764	0.087933	-0.038237
+8.277196	-0.026334	-0.040699	9.794030	0.044499	0.088998	-0.039170
+8.278180	-0.011970	-0.023940	9.806000	0.046631	0.090730	-0.037438
+8.279169	0.007182	0.059851	9.686298	0.047564	0.089665	-0.035040
+8.280170	0.007182	0.002394	9.789242	0.047963	0.085268	-0.034640
+8.281172	0.071821	-0.021546	9.875427	0.049162	0.084735	-0.037172
+8.282150	0.079003	0.000000	9.772483	0.048363	0.087133	-0.038237
+8.283221	0.028729	-0.035911	9.767695	0.045832	0.087533	-0.038770
+8.284153	0.014364	-0.007182	9.817970	0.048230	0.087799	-0.038237
+8.285128	-0.040699	0.000000	9.738967	0.047297	0.088865	-0.039037
+8.286130	0.002394	-0.011970	9.774877	0.043966	0.089665	-0.039303
+8.287124	-0.011970	0.043093	9.743755	0.044100	0.088732	-0.039570
+8.288220	0.011970	-0.004788	9.810788	0.045032	0.086334	-0.036639
+8.289154	-0.014364	-0.050275	9.827546	0.045565	0.086600	-0.035706
+8.290219	0.002394	0.002394	9.777271	0.046364	0.088066	-0.037305
+8.291129	0.002394	-0.050275	9.746149	0.047297	0.088998	-0.037038
+8.292129	0.021546	-0.033517	9.772483	0.046897	0.089665	-0.038237
+8.293171	-0.002394	-0.009576	9.767695	0.046098	0.091130	-0.037704
+8.294220	0.000000	-0.028729	9.724603	0.046364	0.087799	-0.036505
+8.295152	0.002394	0.011970	9.829940	0.046364	0.086334	-0.037038
+8.296128	0.031123	0.014364	9.827546	0.047164	0.086734	-0.036505
+8.297129	-0.004788	0.028729	9.861063	0.047830	0.087933	-0.037438
+8.298128	0.002394	0.059851	9.810788	0.046364	0.089398	-0.038770
+8.299130	-0.009576	-0.004788	9.810788	0.045432	0.090331	-0.037438
+8.300123	0.033517	0.047881	9.873033	0.043966	0.089265	-0.036905
+8.301123	0.062245	-0.016758	9.789242	0.046498	0.088066	-0.037305
+8.302128	0.004788	-0.067033	9.796424	0.047430	0.088199	-0.036772
+8.303128	-0.009576	-0.047881	9.803606	0.046498	0.087133	-0.037971
+8.304130	0.035911	-0.074215	9.815576	0.046631	0.085534	-0.036639
+8.305129	0.043093	0.016758	9.837123	0.047564	0.088199	-0.034773
+8.306222	0.016758	-0.004788	9.858669	0.048629	0.087533	-0.033974
+8.307220	0.026334	-0.021546	9.695874	0.048629	0.089931	-0.033441
+8.308221	-0.023940	-0.007182	9.695874	0.045965	0.088865	-0.035173
+8.309214	0.007182	0.052669	9.798818	0.044766	0.087533	-0.039969
+8.310176	-0.004788	-0.004788	9.817970	0.045965	0.086467	-0.037971
+8.311219	-0.016758	-0.033517	9.791636	0.048629	0.090997	-0.036505
+8.312219	0.011970	0.031123	9.755725	0.047963	0.087933	-0.039570
+8.313220	-0.028729	-0.009576	9.786848	0.046498	0.086467	-0.035839
+8.314208	-0.035911	-0.064639	9.782060	0.045832	0.084735	-0.033175
+8.315238	0.002394	0.002394	9.853881	0.044899	0.086734	-0.030910
+8.316214	0.002394	-0.050275	9.873033	0.046764	0.089931	-0.033574
+8.317219	-0.011970	-0.021546	9.789242	0.048896	0.088998	-0.036106
+8.318221	0.045487	0.040699	9.863457	0.049429	0.086600	-0.036106
+8.319219	0.000000	0.031123	9.865851	0.047164	0.085934	-0.038104
+8.320156	0.011970	0.086186	9.827546	0.045432	0.087133	-0.038104
+8.321153	-0.014364	0.040699	9.868245	0.046231	0.086867	-0.034507
+8.322166	0.009576	0.002394	9.767695	0.048230	0.086201	-0.035040
+8.323185	-0.011970	-0.014364	9.705450	0.046098	0.086067	-0.035306
+8.324147	-0.004788	0.004788	9.746149	0.042234	0.088199	-0.033841
+8.325162	-0.031123	-0.019152	9.686298	0.045032	0.089665	-0.031842
+8.326121	-0.031123	-0.016758	9.750937	0.048096	0.089531	-0.032375
+8.327154	0.016758	-0.043093	9.762907	0.046498	0.087133	-0.033308
+8.328149	-0.007182	0.009576	9.834729	0.045299	0.088466	-0.031709
+8.329208	0.026334	-0.011970	9.829940	0.045698	0.089665	-0.035972
+8.330177	0.004788	-0.028729	9.798818	0.047697	0.089931	-0.034507
+8.331217	0.040699	-0.028729	9.796424	0.048896	0.089798	-0.032375
+8.332219	0.002394	-0.002394	9.856275	0.049429	0.090864	-0.037305
+8.333219	0.004788	0.014364	9.832334	0.047564	0.089665	-0.036905
+8.334221	0.009576	0.007182	9.801212	0.047430	0.089398	-0.034374
+8.335220	0.045487	-0.019152	9.791636	0.048096	0.089531	-0.037438
+8.336218	-0.031123	-0.021546	9.858669	0.048096	0.088732	-0.038237
+8.337221	0.000000	-0.016758	9.841911	0.046231	0.089665	-0.037571
+8.338181	0.035911	-0.019152	9.856275	0.044899	0.091263	-0.036772
+8.339174	0.047881	0.002394	9.803606	0.047564	0.087933	-0.037038
+8.340165	-0.019152	0.040699	9.755725	0.048763	0.088066	-0.035972
+8.341218	-0.007182	-0.016758	9.741361	0.047564	0.087133	-0.037305
+8.342161	-0.021546	-0.033517	9.858669	0.043833	0.089398	-0.034907
+8.343219	0.028729	0.000000	9.870639	0.044366	0.089531	-0.033041
+8.344220	0.045487	0.007182	9.832334	0.045965	0.089665	-0.034773
+8.345221	0.004788	0.019152	9.861063	0.047430	0.090864	-0.035839
+8.346220	-0.052669	-0.016758	9.782060	0.047564	0.090597	-0.035440
+8.347218	-0.031123	0.011970	9.743755	0.047297	0.089265	-0.037172
+8.348183	-0.055063	-0.040699	9.817970	0.047031	0.088332	-0.039969
+8.349193	-0.004788	-0.026334	9.916126	0.046098	0.089132	-0.037305
+8.350153	0.033517	-0.026334	9.801212	0.049162	0.090464	-0.039303
+8.351210	0.011970	-0.023940	9.762907	0.048629	0.088599	-0.038904
+8.352200	-0.016758	0.019152	9.774877	0.048629	0.087933	-0.036905
+8.353218	0.028729	0.007182	9.779666	0.047031	0.087000	-0.036772
+8.354221	-0.007182	0.011970	9.789242	0.047830	0.087133	-0.034773
+8.355157	0.043093	-0.059851	9.827546	0.047430	0.087533	-0.036505
+8.356219	0.002394	-0.011970	9.782060	0.046231	0.085934	-0.035306
+8.357220	-0.014364	-0.047881	9.846699	0.045965	0.083936	-0.034107
+8.358217	0.031123	-0.014364	9.837123	0.047430	0.086334	-0.037172
+8.359174	-0.023940	-0.011970	9.719814	0.048496	0.090331	-0.034773
+8.360168	-0.064639	-0.016758	9.726997	0.049162	0.089398	-0.035573
+8.361166	-0.007182	0.014364	9.822758	0.045965	0.086067	-0.036639
+8.362220	-0.040699	-0.026334	9.870639	0.045032	0.085934	-0.038371
+8.363217	-0.014364	-0.040699	9.820364	0.049162	0.087266	-0.039570
+8.364217	0.047881	-0.064639	9.746149	0.049562	0.088865	-0.039969
+8.365220	0.000000	-0.038305	9.798818	0.047164	0.088865	-0.033041
+8.366222	-0.031123	-0.016758	9.803606	0.045698	0.089265	-0.036106
+8.367219	-0.014364	-0.009576	9.770089	0.045698	0.088865	-0.037305
+8.368177	0.047881	-0.016758	9.717420	0.047963	0.089931	-0.036372
+8.369153	-0.033517	-0.019152	9.789242	0.050228	0.090198	-0.038237
+8.370174	-0.026334	-0.026334	9.853881	0.051694	0.089398	-0.040103
+8.371162	0.023940	0.014364	9.789242	0.049429	0.086600	-0.038637
+8.372152	0.045487	0.040699	9.806000	0.046631	0.084202	-0.035839
+8.373217	0.004788	-0.009576	9.789242	0.047564	0.086600	-0.033708
+8.374177	0.064639	0.026334	9.767695	0.049162	0.089132	-0.032775
+8.375169	0.043093	0.002394	9.801212	0.048363	0.089665	-0.035839
+8.376213	0.023940	0.019152	9.839517	0.047830	0.088332	-0.040236
+8.377223	0.043093	-0.035911	9.839517	0.047963	0.087400	-0.039303
+8.378220	0.059851	-0.009576	9.794030	0.046897	0.086467	-0.039170
+8.379153	0.035911	-0.016758	9.710238	0.047963	0.088066	-0.041568
+8.380173	-0.007182	-0.021546	9.746149	0.048363	0.089132	-0.037838
+8.381152	0.035911	-0.033517	9.748543	0.045032	0.090464	-0.035306
+8.382160	0.002394	-0.052669	9.815576	0.044233	0.090464	-0.034507
+8.383157	-0.002394	-0.047881	9.870639	0.045432	0.087933	-0.035173
+8.384220	0.028729	0.004788	9.911338	0.047164	0.088466	-0.037838
+8.385131	0.021546	-0.035911	9.861063	0.047031	0.090064	-0.038237
+8.386220	0.028729	-0.004788	9.738967	0.046764	0.087400	-0.033841
+8.387183	0.014364	0.004788	9.758119	0.045432	0.087133	-0.034640
+8.388201	0.043093	0.021546	9.827546	0.044899	0.086334	-0.036505
+8.389168	0.026334	-0.021546	9.815576	0.047297	0.089798	-0.036505
+8.390188	-0.011970	0.000000	9.803606	0.049429	0.091263	-0.037704
+8.391177	0.023940	0.021546	9.870639	0.049962	0.090464	-0.036772
+8.392165	-0.016758	-0.009576	9.873033	0.047830	0.089398	-0.037704
+8.393231	0.023940	0.004788	9.770089	0.045698	0.087533	-0.036639
+8.394211	-0.007182	0.057457	9.832334	0.045299	0.087400	-0.039037
+8.395187	0.057457	0.035911	9.794030	0.047564	0.089132	-0.039303
+8.396174	0.035911	0.026334	9.741361	0.049162	0.089132	-0.037571
+8.397173	0.002394	-0.021546	9.719814	0.048230	0.087000	-0.037038
+8.398237	0.021546	0.031123	9.827546	0.046631	0.084868	-0.036639
+8.399232	0.028729	-0.011970	9.794030	0.045965	0.083669	-0.033441
+8.400234	0.000000	-0.026334	9.803606	0.047697	0.085934	-0.032642
+8.401183	-0.002394	-0.007182	9.822758	0.045698	0.088599	-0.037305
+8.402226	-0.057457	0.019152	9.803606	0.046498	0.090464	-0.038371
+8.403178	-0.019152	0.011970	9.808394	0.047697	0.089798	-0.035706
+8.404179	-0.011970	0.009576	9.796424	0.047564	0.089132	-0.035839
+8.405205	0.026334	0.002394	9.808394	0.045032	0.088466	-0.034773
+8.406231	-0.004788	0.000000	9.796424	0.044499	0.087266	-0.034507
+8.407209	-0.031123	0.043093	9.849093	0.046498	0.086600	-0.035173
+8.408165	0.021546	0.014364	9.837123	0.046364	0.087000	-0.034107
+8.409173	0.038305	0.021546	9.846699	0.047297	0.087000	-0.033974
+8.410205	0.047881	0.007182	9.729391	0.047697	0.087533	-0.036505
+8.411156	0.009576	-0.045487	9.738967	0.049429	0.088466	-0.037838
+8.412156	0.007182	-0.004788	9.791636	0.047430	0.090331	-0.037704
+8.413157	0.016758	-0.023940	9.760513	0.045965	0.088865	-0.036372
+8.414215	0.055063	-0.031123	9.734179	0.047430	0.085801	-0.040103
+8.415264	0.043093	0.023940	9.691086	0.046231	0.085934	-0.038504
+8.416227	0.043093	0.019152	9.767695	0.044100	0.085934	-0.034773
+8.417208	0.004788	-0.031123	9.810788	0.044233	0.086467	-0.034640
+8.418168	-0.014364	0.057457	9.789242	0.045032	0.086600	-0.035306
+8.419179	0.021546	0.021546	9.750937	0.044632	0.089531	-0.035173
+8.420234	0.000000	-0.026334	9.834729	0.046897	0.089665	-0.034773
+8.421233	-0.031123	0.009576	9.817970	0.047430	0.088332	-0.035706
+8.422233	0.016758	0.016758	9.806000	0.047697	0.087133	-0.035972
+8.423232	-0.033517	-0.007182	9.815576	0.049695	0.086201	-0.039969
+8.424192	-0.062245	-0.050275	9.772483	0.050628	0.085002	-0.041435
+8.425230	0.026334	-0.043093	9.822758	0.046764	0.086867	-0.037305
+8.426235	0.007182	-0.038305	9.786848	0.046364	0.088865	-0.038237
+8.427233	-0.009576	0.009576	9.703056	0.048763	0.091530	-0.034374
+8.428234	0.002394	0.009576	9.784454	0.046897	0.090464	-0.038371
+8.429233	0.021546	-0.021546	9.774877	0.046498	0.088998	-0.037172
+8.430234	0.014364	-0.028729	9.825152	0.047430	0.086467	-0.037971
+8.431232	0.009576	-0.055063	9.729391	0.049962	0.085801	-0.035839
+8.432231	0.055063	-0.055063	9.810788	0.046631	0.086867	-0.035173
+8.433185	0.045487	-0.009576	9.724603	0.045698	0.088998	-0.037038
+8.434166	0.067033	0.002394	9.741361	0.046364	0.089931	-0.039436
+8.435203	0.011970	-0.004788	9.820364	0.048896	0.088865	-0.039436
+8.436170	-0.038305	-0.021546	9.837123	0.049029	0.086334	-0.036505
+8.437234	-0.045487	-0.052669	9.817970	0.046631	0.087266	-0.035440
+8.438234	0.064639	0.007182	9.827546	0.046231	0.086467	-0.035306
+8.439208	0.026334	-0.016758	9.844305	0.047164	0.086334	-0.033308
+8.440229	-0.026334	-0.055063	9.865851	0.047297	0.087000	-0.034374
+8.441235	0.047881	-0.004788	9.822758	0.048896	0.088732	-0.036106
+8.442234	0.000000	0.045487	9.896974	0.048629	0.089132	-0.033308
+8.443234	0.019152	-0.009576	9.877821	0.045965	0.086867	-0.036106
+8.444234	0.059851	0.050275	9.782060	0.046498	0.087533	-0.036772
+8.445198	0.026334	0.045487	9.789242	0.047164	0.087133	-0.035440
+8.446229	0.014364	0.038305	9.794030	0.047164	0.088332	-0.036239
+8.447231	-0.019152	0.023940	9.794030	0.045965	0.089398	-0.037438
+8.448188	-0.014364	0.059851	9.829940	0.047031	0.086600	-0.036639
+8.449233	0.021546	-0.019152	9.892186	0.045832	0.086067	-0.036505
+8.450233	0.090974	-0.035911	9.810788	0.046631	0.087533	-0.034374
+8.451205	0.086186	-0.043093	9.806000	0.048230	0.088599	-0.033574
+8.452233	0.035911	-0.062245	9.846699	0.048629	0.089132	-0.034107
+8.453232	-0.026334	-0.045487	9.846699	0.047697	0.089798	-0.036372
+8.454233	-0.035911	0.000000	9.846699	0.047164	0.089265	-0.041168
+8.455243	0.007182	-0.040699	9.817970	0.047297	0.090064	-0.039170
+8.456179	0.004788	0.002394	9.772483	0.046098	0.088865	-0.033841
+8.457233	-0.047881	0.014364	9.822758	0.044899	0.088599	-0.033041
+8.458232	-0.021546	0.007182	9.767695	0.045432	0.087133	-0.034640
+8.459232	0.043093	0.011970	9.772483	0.045565	0.083936	-0.036239
+8.460189	0.055063	-0.007182	9.791636	0.045698	0.084469	-0.036239
+8.461215	0.007182	-0.009576	9.829940	0.047297	0.088332	-0.037305
+8.462210	0.047881	-0.009576	9.858669	0.047430	0.089398	-0.037038
+8.463276	0.023940	0.050275	9.808394	0.047697	0.087400	-0.037038
+8.464275	0.009576	-0.007182	9.770089	0.049296	0.088066	-0.037971
+8.465231	0.014364	-0.074215	9.762907	0.048629	0.085801	-0.039969
+8.466274	0.009576	-0.045487	9.755725	0.046631	0.085668	-0.038237
+8.467273	0.009576	-0.009576	9.688692	0.047430	0.086334	-0.036372
+8.468275	-0.021546	-0.019152	9.760513	0.045432	0.088066	-0.035839
+8.469198	-0.023940	-0.007182	9.753331	0.045032	0.087666	-0.033708
+8.470280	0.033517	-0.019152	9.767695	0.046364	0.085534	-0.035173
+8.471275	0.028729	-0.038305	9.777271	0.047430	0.086734	-0.040369
+8.472274	-0.019152	-0.023940	9.750937	0.047031	0.087266	-0.039303
+8.473229	0.019152	-0.011970	9.829940	0.046498	0.088066	-0.036772
+8.474255	-0.023940	-0.019152	9.796424	0.045299	0.089398	-0.035839
+8.475222	-0.023940	-0.086186	9.786848	0.046498	0.089798	-0.033841
+8.476273	0.019152	-0.055063	9.832334	0.047297	0.088332	-0.035306
+8.477274	-0.050275	-0.009576	9.815576	0.045965	0.086600	-0.036905
+8.478274	0.002394	0.011970	9.715026	0.046897	0.087133	-0.040236
+8.479269	0.031123	-0.031123	9.741361	0.046897	0.085668	-0.034907
+8.480269	-0.009576	0.019152	9.789242	0.043300	0.083403	-0.032775
+8.481270	0.002394	-0.023940	9.832334	0.045965	0.087533	-0.036905
+8.482208	0.002394	0.014364	9.798818	0.048496	0.089798	-0.037172
+8.483206	0.004788	0.028729	9.858669	0.046897	0.088599	-0.034907
+8.484187	-0.023940	-0.028729	9.801212	0.046498	0.085934	-0.036106
+8.485179	0.011970	-0.023940	9.777271	0.047297	0.085268	-0.039436
+8.486278	0.062245	-0.023940	9.726997	0.048496	0.084469	-0.035972
+8.487274	0.028729	-0.059851	9.762907	0.048363	0.084602	-0.035839
+8.488276	0.014364	-0.045487	9.837123	0.046631	0.089132	-0.034773
+8.489209	0.067033	-0.033517	9.899368	0.047164	0.090331	-0.034640
+8.490276	0.011970	0.002394	9.815576	0.046764	0.089665	-0.034640
+8.491275	-0.014364	-0.071821	9.772483	0.045432	0.087266	-0.036372
+8.492215	-0.014364	-0.009576	9.786848	0.044499	0.087799	-0.036905
+8.493253	0.014364	0.016758	9.820364	0.046364	0.088865	-0.035706
+8.494220	0.033517	-0.023940	9.832334	0.047697	0.089398	-0.036639
+8.495171	0.007182	-0.033517	9.817970	0.046098	0.089132	-0.037704
+8.496172	-0.002394	-0.011970	9.813182	0.043700	0.087133	-0.035972
+8.497175	0.009576	-0.009576	9.798818	0.043433	0.088599	-0.034240
+8.498181	0.055063	0.004788	9.693480	0.046364	0.089931	-0.035839
+8.499274	0.004788	-0.011970	9.774877	0.046897	0.089665	-0.037971
+8.500211	-0.038305	-0.031123	9.851487	0.048230	0.088865	-0.037305
+8.501231	-0.007182	0.021546	9.801212	0.047564	0.089132	-0.036772
+8.502210	0.007182	-0.016758	9.743755	0.045698	0.089398	-0.038770
+8.503271	0.011970	-0.052669	9.760513	0.046098	0.088732	-0.037305
+8.504274	0.007182	-0.026334	9.770089	0.046098	0.088332	-0.036905
+8.505254	0.023940	0.026334	9.750937	0.047031	0.086067	-0.037704
+8.506276	0.000000	-0.007182	9.715026	0.046631	0.086334	-0.039037
+8.507276	0.009576	-0.009576	9.810788	0.045432	0.086467	-0.038371
+8.508235	-0.007182	-0.002394	9.846699	0.046631	0.088332	-0.040769
+8.509274	-0.050275	-0.028729	9.853881	0.047963	0.089265	-0.039836
+8.510226	-0.028729	-0.016758	9.808394	0.048629	0.088199	-0.036905
+8.511230	-0.014364	-0.021546	9.796424	0.045832	0.087000	-0.035839
+8.512221	-0.033517	-0.004788	9.808394	0.044899	0.089265	-0.034507
+8.513275	-0.009576	-0.035911	9.746149	0.043700	0.085801	-0.037571
+8.514278	-0.009576	-0.033517	9.738967	0.045698	0.087933	-0.041835
+8.515245	0.052669	-0.019152	9.803606	0.045698	0.089132	-0.039969
+8.516274	0.002394	0.023940	9.906550	0.048096	0.087933	-0.035440
+8.517273	-0.004788	0.011970	9.908944	0.046231	0.087266	-0.034107
+8.518239	0.026334	-0.016758	9.899368	0.045698	0.087266	-0.034640
+8.519192	0.023940	-0.011970	9.846699	0.047830	0.090597	-0.036239
+8.520228	-0.007182	-0.031123	9.794030	0.049962	0.090864	-0.037305
+8.521273	0.055063	-0.047881	9.806000	0.048629	0.086734	-0.037305
+8.522278	0.052669	0.014364	9.829940	0.047031	0.086201	-0.037571
+8.523275	0.045487	-0.004788	9.868245	0.045832	0.085668	-0.035306
+8.524274	0.035911	0.023940	9.849093	0.046098	0.086201	-0.036772
+8.525275	0.016758	0.007182	9.786848	0.044366	0.087000	-0.039170
+8.526276	0.026334	0.026334	9.810788	0.044766	0.087799	-0.038104
+8.527275	-0.055063	-0.079003	9.782060	0.046764	0.091530	-0.038371
+8.528234	-0.052669	-0.007182	9.839517	0.047564	0.090864	-0.034374
+8.529235	0.016758	-0.004788	9.875427	0.048096	0.087666	-0.035306
+8.530277	0.064639	-0.021546	9.803606	0.045165	0.085934	-0.039570
+8.531192	0.052669	-0.007182	9.734179	0.041968	0.086734	-0.037704
+8.532196	0.028729	-0.014364	9.820364	0.042900	0.089398	-0.034907
+8.533184	0.043093	-0.007182	9.825152	0.046498	0.090331	-0.034507
+8.534183	0.021546	-0.023940	9.810788	0.046897	0.088998	-0.035040
+8.535204	0.021546	-0.033517	9.863457	0.047430	0.087266	-0.033974
+8.536205	0.045487	-0.011970	9.882609	0.046364	0.086467	-0.034907
+8.537181	0.052669	-0.026334	9.808394	0.049029	0.086600	-0.038904
+8.538203	0.000000	-0.052669	9.736573	0.050228	0.088599	-0.038237
+8.539201	-0.007182	-0.052669	9.789242	0.048496	0.090064	-0.039170
+8.540246	0.019152	-0.033517	9.765301	0.047830	0.088998	-0.036239
+8.541189	0.021546	0.045487	9.801212	0.047164	0.087533	-0.036639
+8.542245	0.035911	-0.014364	9.801212	0.048363	0.086334	-0.038237
+8.543275	-0.028729	0.071821	9.700662	0.046631	0.085534	-0.034640
+8.544274	-0.011970	0.055063	9.770089	0.046098	0.085668	-0.033041
+8.545275	-0.009576	-0.007182	9.758119	0.045432	0.088466	-0.036505
+8.546278	0.002394	0.000000	9.777271	0.044899	0.086867	-0.039170
+8.547189	-0.014364	0.019152	9.762907	0.046364	0.085401	-0.038104
+8.548203	-0.016758	-0.016758	9.736573	0.047164	0.088998	-0.036772
+8.549270	0.000000	-0.004788	9.724603	0.048496	0.090864	-0.036106
+8.550218	-0.023940	-0.064639	9.741361	0.048363	0.089398	-0.036905
+8.551196	0.007182	-0.050275	9.729391	0.045698	0.088199	-0.037305
+8.552273	0.009576	0.002394	9.674328	0.045832	0.087799	-0.035173
+8.553274	0.009576	0.033517	9.719814	0.046897	0.088466	-0.033841
+8.554278	0.000000	0.016758	9.794030	0.048363	0.090464	-0.034240
+8.555272	0.016758	-0.002394	9.870639	0.045032	0.089531	-0.038104
+8.556211	0.035911	-0.004788	9.774877	0.043700	0.088466	-0.038770
+8.557255	-0.009576	0.043093	9.726997	0.044899	0.088998	-0.036505
+8.558217	-0.007182	-0.026334	9.779666	0.047564	0.087133	-0.036239
+8.559218	-0.004788	-0.004788	9.765301	0.048496	0.088466	-0.035306
+8.560211	0.038305	0.016758	9.801212	0.047164	0.089665	-0.037038
+8.561276	0.023940	-0.002394	9.839517	0.047297	0.086467	-0.037571
+8.562232	0.011970	0.014364	9.844305	0.048096	0.083403	-0.034907
+8.563274	0.004788	0.026334	9.806000	0.047031	0.087133	-0.035839
+8.564274	0.026334	0.028729	9.832334	0.045965	0.088732	-0.036372
+8.565229	0.055063	0.007182	9.837123	0.045565	0.087400	-0.037038
+8.566258	0.067033	-0.021546	9.815576	0.046098	0.087400	-0.035706
+8.567275	0.062245	-0.023940	9.734179	0.047164	0.086600	-0.037571
+8.568212	0.055063	0.016758	9.724603	0.048230	0.087400	-0.037305
+8.569212	0.055063	0.004788	9.794030	0.048363	0.088998	-0.036505
+8.570278	0.028729	0.023940	9.822758	0.047031	0.086734	-0.038504
+8.571274	0.050275	0.000000	9.765301	0.047297	0.086067	-0.038770
+8.572273	0.045487	-0.014364	9.849093	0.047564	0.087000	-0.037038
+8.573254	0.026334	-0.035911	9.791636	0.048496	0.086734	-0.035306
+8.574210	0.028729	-0.019152	9.791636	0.047830	0.086600	-0.036106
+8.575270	0.069427	-0.031123	9.724603	0.047430	0.087933	-0.038237
+8.576274	0.045487	-0.052669	9.789242	0.046764	0.089931	-0.038104
+8.577277	0.011970	-0.023940	9.796424	0.045965	0.089531	-0.038371
+8.578277	-0.007182	0.004788	9.784454	0.044899	0.087799	-0.036106
+8.579246	-0.021546	0.019152	9.844305	0.046764	0.087533	-0.035040
+8.580274	-0.019152	0.009576	9.856275	0.047564	0.088066	-0.038371
+8.581275	0.002394	0.007182	9.748543	0.046098	0.088066	-0.038371
+8.582228	-0.002394	-0.016758	9.717420	0.046498	0.089665	-0.034773
+8.583202	-0.007182	-0.052669	9.777271	0.049429	0.086867	-0.036505
+8.584208	0.009576	-0.019152	9.827546	0.049162	0.087533	-0.036239
+8.585225	0.004788	-0.038305	9.858669	0.047297	0.087266	-0.037038
+8.586276	-0.007182	0.011970	9.782060	0.046098	0.087133	-0.037038
+8.587273	0.023940	-0.009576	9.834729	0.045965	0.088466	-0.039570
+8.588214	0.038305	-0.052669	9.815576	0.045832	0.087400	-0.039170
+8.589202	-0.011970	-0.021546	9.817970	0.046764	0.085801	-0.040369
+8.590276	-0.033517	0.050275	9.798818	0.047830	0.087799	-0.039436
+8.591274	0.014364	0.014364	9.808394	0.047564	0.089798	-0.034640
+8.592230	-0.002394	-0.021546	9.767695	0.049429	0.089665	-0.031709
+8.593242	-0.007182	-0.026334	9.794030	0.048363	0.087533	-0.034374
+8.594282	-0.035911	-0.002394	9.794030	0.047564	0.087799	-0.037438
+8.595274	-0.021546	-0.040699	9.791636	0.046231	0.088199	-0.038770
+8.596272	0.000000	-0.031123	9.794030	0.046764	0.088466	-0.038371
+8.597273	0.007182	-0.007182	9.827546	0.048096	0.089398	-0.036905
+8.598278	-0.023940	-0.019152	9.825152	0.047830	0.087933	-0.035173
+8.599273	0.004788	0.011970	9.748543	0.045565	0.088199	-0.036905
+8.600273	0.019152	0.035911	9.748543	0.046498	0.087400	-0.035440
+8.601227	0.000000	0.007182	9.782060	0.050495	0.087666	-0.036239
+8.602227	0.004788	-0.019152	9.774877	0.049828	0.089132	-0.039170
+8.603274	0.033517	0.007182	9.834729	0.046631	0.089931	-0.037305
+8.604275	-0.004788	-0.011970	9.856275	0.045698	0.089265	-0.037305
+8.605273	0.019152	0.000000	9.920914	0.047164	0.087400	-0.035440
+8.606247	0.043093	0.040699	9.829940	0.044499	0.087000	-0.035440
+8.607273	0.026334	0.031123	9.789242	0.043300	0.086201	-0.036639
+8.608271	0.038305	-0.071821	9.885003	0.045965	0.087533	-0.034640
+8.609190	-0.004788	-0.059851	9.885003	0.049828	0.088466	-0.033041
+8.610202	-0.055063	0.019152	9.748543	0.048763	0.089531	-0.034107
+8.611207	-0.014364	0.026334	9.741361	0.047164	0.090997	-0.037438
+8.612231	-0.009576	0.016758	9.772483	0.047430	0.090331	-0.038504
+8.613211	0.038305	0.057457	9.882609	0.047031	0.086867	-0.036639
+8.614279	0.059851	0.023940	9.806000	0.044100	0.086067	-0.036106
+8.615275	0.038305	-0.016758	9.726997	0.046098	0.087266	-0.037038
+8.616275	0.083792	0.000000	9.784454	0.048496	0.086201	-0.037305
+8.617249	0.055063	-0.016758	9.810788	0.047564	0.085534	-0.035306
+8.618236	0.040699	-0.043093	9.820364	0.049162	0.086600	-0.036239
+8.619195	-0.011970	0.007182	9.806000	0.049562	0.087400	-0.036372
+8.620274	-0.019152	0.011970	9.832334	0.047564	0.089265	-0.035706
+8.621239	-0.035911	0.016758	9.875427	0.044366	0.088199	-0.035706
+8.622216	0.035911	-0.028729	9.791636	0.044632	0.089132	-0.034374
+8.623227	0.014364	0.002394	9.750937	0.049162	0.089265	-0.034240
+8.624206	-0.035911	-0.074215	9.806000	0.048230	0.089398	-0.036239
+8.625251	0.011970	-0.069427	9.815576	0.047430	0.087266	-0.036239
+8.626280	0.000000	-0.052669	9.791636	0.047830	0.086600	-0.033974
+8.627274	-0.021546	-0.038305	9.801212	0.044632	0.087266	-0.038770
+8.628237	-0.021546	0.009576	9.791636	0.046498	0.087133	-0.041168
+8.629273	-0.021546	-0.043093	9.856275	0.047697	0.086467	-0.037971
+8.630243	0.035911	-0.026334	9.801212	0.047430	0.088599	-0.037438
+8.631228	0.043093	0.000000	9.786848	0.048896	0.089265	-0.037438
+8.632270	0.031123	-0.050275	9.767695	0.048096	0.088332	-0.036106
+8.633202	0.019152	-0.086186	9.832334	0.045299	0.087933	-0.034107
+8.634212	0.002394	-0.062245	9.844305	0.045565	0.087666	-0.036505
+8.635180	-0.035911	-0.011970	9.772483	0.048230	0.087266	-0.037305
+8.636210	0.014364	0.019152	9.736573	0.048896	0.088066	-0.037305
+8.637203	0.045487	-0.009576	9.767695	0.048496	0.087133	-0.035972
+8.638275	0.033517	-0.009576	9.808394	0.046897	0.088332	-0.035972
+8.639212	-0.035911	-0.019152	9.796424	0.046631	0.088199	-0.037038
+8.640230	0.028729	-0.033517	9.794030	0.046231	0.087133	-0.033441
+8.641203	0.038305	-0.004788	9.834729	0.044899	0.087133	-0.034507
+8.642214	0.009576	0.007182	9.794030	0.047963	0.088599	-0.035173
+8.643195	0.016758	0.016758	9.765301	0.047963	0.088199	-0.035573
+8.644200	0.002394	0.031123	9.803606	0.045299	0.089132	-0.034507
+8.645200	-0.011970	0.019152	9.801212	0.046098	0.088998	-0.038104
+8.646203	0.004788	0.021546	9.861063	0.046231	0.089132	-0.038371
+8.647195	0.007182	0.033517	9.825152	0.045565	0.089265	-0.037172
+8.648201	0.009576	-0.033517	9.779666	0.044632	0.088599	-0.037305
+8.649176	0.019152	-0.021546	9.782060	0.043700	0.088599	-0.034374
+8.650199	0.067033	0.002394	9.820364	0.045565	0.089132	-0.035040
+8.651200	0.011970	0.021546	9.829940	0.047697	0.090464	-0.033841
+8.652186	-0.035911	0.011970	9.743755	0.047430	0.088199	-0.036505
+8.653202	-0.057457	0.038305	9.712632	0.046897	0.087533	-0.036505
+8.654138	-0.045487	0.050275	9.681510	0.046231	0.089398	-0.035706
+8.655107	-0.023940	0.031123	9.731785	0.046364	0.088599	-0.033041
+8.656136	-0.019152	0.009576	9.810788	0.046098	0.088865	-0.031043
+8.657112	0.031123	-0.019152	9.777271	0.046231	0.088732	-0.034374
+8.658111	0.064639	-0.023940	9.782060	0.046897	0.088199	-0.033708
+8.659136	0.067033	-0.016758	9.770089	0.047697	0.088599	-0.034773
+8.660135	0.047881	0.031123	9.806000	0.049162	0.088599	-0.037038
+8.661134	-0.019152	0.021546	9.810788	0.049162	0.086867	-0.039836
+8.662136	-0.021546	0.045487	9.710238	0.048096	0.086467	-0.041568
+8.663141	-0.021546	0.040699	9.748543	0.048230	0.087933	-0.035173
+8.664099	-0.021546	0.040699	9.748543	0.047164	0.089531	-0.032908
+8.665179	-0.026334	-0.011970	9.820364	0.046897	0.088066	-0.036772
+8.666185	0.002394	0.002394	9.846699	0.046764	0.088066	-0.037971
+8.667111	-0.007182	-0.031123	9.846699	0.046897	0.086600	-0.035573
+8.668207	0.038305	-0.007182	9.865851	0.049429	0.086600	-0.037305
+8.669135	0.035911	-0.050275	9.796424	0.047297	0.086867	-0.036106
+8.670216	0.016758	-0.040699	9.722208	0.046231	0.087666	-0.038104
+8.671209	-0.011970	-0.047881	9.750937	0.044632	0.087933	-0.036106
+8.672188	-0.019152	-0.047881	9.789242	0.044366	0.087000	-0.035306
+8.673190	0.002394	-0.055063	9.825152	0.044100	0.087400	-0.036639
+8.674178	-0.004788	-0.038305	9.753331	0.046897	0.088466	-0.036639
+8.675187	0.009576	-0.028729	9.767695	0.048096	0.088066	-0.038770
+8.676187	0.007182	-0.033517	9.806000	0.048763	0.090730	-0.039436
+8.677168	-0.021546	0.007182	9.832334	0.049828	0.085934	-0.038104
+8.678138	-0.026334	0.026334	9.779666	0.049695	0.085534	-0.036106
+8.679187	0.023940	-0.014364	9.808394	0.047297	0.087666	-0.036106
+8.680150	0.079003	-0.019152	9.791636	0.050228	0.087533	-0.038637
+8.681189	0.035911	0.028729	9.772483	0.051028	0.087799	-0.037438
+8.682191	0.000000	-0.009576	9.736573	0.047830	0.086600	-0.037971
+8.683173	-0.043093	-0.009576	9.755725	0.044499	0.087000	-0.037971
+8.684122	-0.019152	0.038305	9.765301	0.045299	0.088732	-0.035972
+8.685108	0.002394	0.002394	9.767695	0.045832	0.088732	-0.034773
+8.686126	-0.007182	0.009576	9.822758	0.047430	0.087533	-0.035306
+8.687188	-0.002394	-0.007182	9.791636	0.047164	0.087533	-0.035306
+8.688173	0.028729	-0.031123	9.786848	0.047031	0.088332	-0.033841
+8.689126	0.019152	-0.064639	9.717420	0.046098	0.086067	-0.034507
+8.690189	0.016758	-0.028729	9.755725	0.044766	0.084069	-0.035306
+8.691188	0.074215	-0.026334	9.806000	0.046231	0.085934	-0.038104
+8.692188	0.007182	-0.052669	9.875427	0.047164	0.088732	-0.039703
+8.693187	-0.023940	0.026334	9.834729	0.044632	0.088332	-0.036505
+8.694190	0.009576	-0.023940	9.753331	0.043700	0.086201	-0.035706
+8.695187	0.007182	-0.016758	9.698268	0.046897	0.086867	-0.036106
+8.696188	-0.035911	-0.040699	9.844305	0.047430	0.087533	-0.039037
+8.697187	0.000000	-0.011970	9.825152	0.047031	0.089132	-0.042234
+8.698170	-0.021546	-0.004788	9.817970	0.045165	0.089132	-0.039836
+8.699144	0.004788	0.009576	9.825152	0.045965	0.087266	-0.036905
+8.700138	0.009576	-0.031123	9.822758	0.048763	0.087000	-0.031709
+8.701122	-0.004788	-0.035911	9.834729	0.047430	0.087533	-0.037971
+8.702120	0.033517	-0.023940	9.849093	0.045832	0.088599	-0.040369
+8.703181	0.026334	-0.023940	9.889792	0.046498	0.089531	-0.037038
+8.704183	-0.002394	-0.040699	9.882609	0.046897	0.088466	-0.038904
+8.705142	0.033517	0.002394	9.829940	0.047297	0.088732	-0.036372
+8.706128	0.000000	0.009576	9.794030	0.047830	0.085934	-0.037704
+8.707155	0.019152	-0.011970	9.777271	0.046498	0.087933	-0.037704
+8.708119	0.028729	-0.055063	9.794030	0.047297	0.088599	-0.036106
+8.709154	0.043093	0.000000	9.834729	0.047031	0.086867	-0.036106
+8.710117	0.014364	-0.028729	9.870639	0.047164	0.087666	-0.035706
+8.711185	0.004788	-0.071821	9.808394	0.047697	0.087933	-0.036239
+8.712185	-0.004788	-0.038305	9.803606	0.047297	0.085801	-0.040236
+8.713187	-0.009576	0.026334	9.870639	0.049296	0.084868	-0.036505
+8.714189	-0.014364	-0.004788	9.841911	0.048496	0.086467	-0.035040
+8.715185	-0.004788	-0.021546	9.889792	0.047297	0.088732	-0.035440
+8.716181	-0.026334	0.021546	9.851487	0.045432	0.088066	-0.035306
+8.717141	-0.011970	-0.009576	9.810788	0.045965	0.087933	-0.036905
+8.718123	-0.040699	-0.011970	9.825152	0.047564	0.088865	-0.037704
+8.719167	-0.007182	-0.009576	9.875427	0.048629	0.087266	-0.039303
+8.720171	0.035911	-0.035911	9.901762	0.048096	0.087933	-0.042900
+8.721191	0.057457	0.016758	9.918520	0.047164	0.089398	-0.037838
+8.722184	0.033517	0.000000	9.825152	0.047697	0.087533	-0.034507
+8.723185	0.035911	-0.004788	9.825152	0.047830	0.083936	-0.035040
+8.724171	0.052669	-0.026334	9.817970	0.048896	0.084868	-0.034640
+8.725122	0.043093	-0.035911	9.774877	0.051161	0.087799	-0.035839
+8.726186	0.007182	0.000000	9.815576	0.049562	0.091263	-0.034374
+8.727185	0.023940	0.011970	9.877821	0.044366	0.090198	-0.035440
+8.728184	0.016758	0.045487	9.834729	0.043433	0.087799	-0.036106
+8.729175	-0.016758	0.000000	9.798818	0.045965	0.086334	-0.038371
+8.730186	0.038305	-0.023940	9.784454	0.048096	0.085668	-0.037971
+8.731187	0.021546	-0.009576	9.750937	0.046631	0.087133	-0.036505
+8.732141	0.026334	-0.002394	9.679116	0.043700	0.086201	-0.033574
+8.733124	0.011970	0.045487	9.834729	0.044899	0.085934	-0.033841
+8.734139	-0.007182	-0.028729	9.798818	0.047164	0.088066	-0.037571
+8.735126	0.007182	-0.040699	9.796424	0.049029	0.087000	-0.037438
+8.736138	-0.014364	-0.021546	9.791636	0.048496	0.090331	-0.036505
+8.737135	0.023940	-0.031123	9.810788	0.047830	0.089931	-0.037704
+8.738146	0.021546	0.004788	9.786848	0.045965	0.087666	-0.036239
+8.739184	-0.009576	0.002394	9.829940	0.047430	0.086600	-0.035839
+8.740137	-0.007182	0.004788	9.829940	0.049429	0.088066	-0.038237
+8.741151	-0.052669	-0.026334	9.801212	0.048496	0.088066	-0.037704
+8.742196	-0.009576	-0.026334	9.796424	0.047697	0.087933	-0.037704
+8.743182	-0.019152	-0.021546	9.760513	0.045565	0.090198	-0.036106
+8.744186	-0.023940	0.002394	9.825152	0.046764	0.087533	-0.035573
+8.745187	0.038305	-0.002394	9.875427	0.047697	0.086334	-0.035040
+8.746190	0.000000	-0.011970	9.786848	0.048363	0.086867	-0.034907
+8.747171	-0.002394	-0.009576	9.693480	0.046897	0.088332	-0.037172
+8.748141	0.021546	-0.019152	9.724603	0.045165	0.090064	-0.037571
+8.749136	0.002394	0.045487	9.825152	0.045299	0.090730	-0.037172
+8.750156	-0.045487	0.009576	9.758119	0.044233	0.088599	-0.036639
+8.751152	-0.028729	-0.045487	9.808394	0.045165	0.084469	-0.033441
+8.752182	0.033517	-0.047881	9.844305	0.044366	0.084469	-0.035440
+8.753187	0.040699	-0.074215	9.801212	0.046498	0.086867	-0.035839
+8.754190	0.031123	-0.059851	9.774877	0.046631	0.088466	-0.034507
+8.755181	-0.014364	-0.040699	9.791636	0.046364	0.088466	-0.034773
+8.756152	0.002394	0.000000	9.741361	0.046764	0.087400	-0.035839
+8.757188	0.000000	0.004788	9.885003	0.047830	0.087533	-0.035972
+8.758187	0.052669	0.026334	9.853881	0.046498	0.085002	-0.033841
+8.759170	0.021546	-0.031123	9.851487	0.046498	0.085534	-0.034374
+8.760137	0.009576	-0.004788	9.762907	0.048230	0.087666	-0.034640
+8.761140	0.011970	0.023940	9.746149	0.046764	0.086201	-0.033175
+8.762143	0.014364	-0.050275	9.841911	0.044366	0.085934	-0.033708
+8.763177	-0.021546	-0.014364	9.856275	0.044233	0.087933	-0.034773
+8.764176	0.016758	-0.019152	9.782060	0.046364	0.088865	-0.035440
+8.765185	0.014364	-0.014364	9.806000	0.047564	0.089398	-0.036772
+8.766187	0.021546	0.040699	9.820364	0.046897	0.089398	-0.036505
+8.767140	0.028729	0.040699	9.801212	0.045698	0.089398	-0.039170
+8.768127	-0.047881	-0.019152	9.846699	0.047164	0.086867	-0.039836
+8.769140	0.031123	-0.021546	9.858669	0.048363	0.085534	-0.037038
+8.770189	-0.052669	-0.069427	9.820364	0.047697	0.087266	-0.032908
+8.771185	0.026334	-0.043093	9.837123	0.047297	0.086867	-0.034374
+8.772174	0.007182	0.009576	9.786848	0.049828	0.087666	-0.037438
+8.773128	0.009576	-0.016758	9.782060	0.048230	0.087400	-0.037172
+8.774185	-0.011970	-0.019152	9.844305	0.046098	0.087000	-0.032642
+8.775187	-0.023940	-0.040699	9.880215	0.046631	0.086334	-0.030243
+8.776187	-0.021546	-0.011970	9.820364	0.048896	0.086734	-0.035306
+8.777188	0.002394	-0.023940	9.796424	0.048896	0.087266	-0.038770
+8.778184	0.033517	-0.004788	9.817970	0.047297	0.088466	-0.037172
+8.779185	0.009576	-0.019152	9.870639	0.048896	0.086867	-0.034240
+8.780187	0.004788	-0.002394	9.849093	0.048629	0.087133	-0.035839
+8.781182	0.016758	-0.038305	9.870639	0.043167	0.090198	-0.037305
+8.782157	0.004788	-0.079003	9.904156	0.044766	0.091663	-0.036772
+8.783160	0.031123	-0.079003	9.832334	0.046364	0.088332	-0.038371
+8.784121	0.004788	-0.004788	9.829940	0.047830	0.086467	-0.037438
+8.785186	0.040699	-0.011970	9.882609	0.049562	0.087000	-0.037438
+8.786166	0.043093	-0.023940	9.853881	0.048763	0.089798	-0.038371
+8.787185	0.040699	0.002394	9.825152	0.045432	0.089665	-0.037838
+8.788122	0.043093	-0.028729	9.829940	0.044499	0.086867	-0.036239
+8.789185	-0.002394	0.000000	9.841911	0.046098	0.083536	-0.035040
+8.790188	0.000000	0.019152	9.856275	0.047564	0.085934	-0.037305
+8.791186	-0.062245	0.011970	9.794030	0.048763	0.088599	-0.036639
+8.792173	-0.052669	0.016758	9.760513	0.051161	0.086734	-0.032775
+8.793183	-0.031123	-0.016758	9.786848	0.050228	0.088599	-0.036106
+8.794187	-0.014364	0.023940	9.746149	0.049962	0.089798	-0.036905
+8.795157	0.009576	-0.007182	9.798818	0.049296	0.089398	-0.037838
+8.796093	0.011970	-0.026334	9.837123	0.045432	0.087933	-0.039703
+8.797110	0.002394	0.014364	9.837123	0.044766	0.088199	-0.037704
+8.798172	-0.002394	-0.021546	9.772483	0.046897	0.088332	-0.035306
+8.799173	-0.004788	-0.014364	9.796424	0.046498	0.090597	-0.037838
+8.800155	-0.023940	0.009576	9.794030	0.047830	0.090331	-0.041435
+8.801155	0.023940	0.038305	9.810788	0.047297	0.088732	-0.038770
+8.802175	0.040699	0.002394	9.772483	0.049695	0.088332	-0.035173
+8.803176	0.021546	-0.055063	9.798818	0.046897	0.086734	-0.034374
+8.804152	-0.007182	-0.019152	9.822758	0.045832	0.086067	-0.035573
+8.805170	-0.014364	-0.035911	9.849093	0.044899	0.085135	-0.034640
+8.806154	-0.069427	-0.026334	9.808394	0.048230	0.087000	-0.035306
+8.807174	-0.052669	-0.011970	9.851487	0.047963	0.088466	-0.034907
+8.808176	-0.011970	0.021546	9.796424	0.047697	0.089398	-0.038104
+8.809175	-0.043093	0.009576	9.760513	0.048096	0.092729	-0.038104
+8.810138	-0.009576	-0.040699	9.750937	0.047297	0.090464	-0.036106
+8.811173	0.055063	-0.016758	9.789242	0.046364	0.085534	-0.036372
+8.812174	0.064639	0.000000	9.892186	0.047430	0.086334	-0.036372
+8.813175	-0.004788	-0.035911	9.865851	0.047164	0.088199	-0.036772
+8.814092	-0.021546	-0.047881	9.796424	0.046231	0.089665	-0.040769
+8.815112	-0.023940	-0.050275	9.825152	0.047564	0.089798	-0.039570
+8.816160	-0.031123	-0.023940	9.813182	0.050228	0.090198	-0.036639
+8.817173	-0.031123	-0.016758	9.817970	0.051294	0.089665	-0.035706
+8.818134	0.021546	-0.050275	9.815576	0.050761	0.089398	-0.035573
+8.819129	0.014364	0.023940	9.841911	0.046631	0.089931	-0.035173
+8.820130	-0.028729	0.100550	9.729391	0.045965	0.090064	-0.035972
+8.821128	0.011970	0.000000	9.705450	0.047430	0.088865	-0.037571
+8.822130	0.043093	-0.011970	9.681510	0.045165	0.089132	-0.036106
+8.823128	-0.014364	-0.057457	9.762907	0.045965	0.088599	-0.035040
+8.824150	-0.050275	-0.038305	9.820364	0.047564	0.088466	-0.037704
+8.825147	-0.050275	0.000000	9.803606	0.048763	0.089398	-0.038104
+8.826152	-0.038305	0.016758	9.791636	0.049029	0.086734	-0.036772
+8.827149	-0.002394	0.043093	9.820364	0.045565	0.086867	-0.035839
+8.828120	-0.059851	-0.002394	9.887397	0.045565	0.087000	-0.036772
+8.829170	0.009576	-0.019152	9.832334	0.046231	0.086334	-0.039037
+8.830197	0.019152	-0.047881	9.798818	0.045832	0.084735	-0.039037
+8.831168	0.021546	-0.079003	9.899368	0.046631	0.084335	-0.036505
+8.832166	0.040699	-0.016758	9.806000	0.047830	0.088066	-0.037438
+8.833138	0.016758	-0.014364	9.767695	0.049162	0.088332	-0.038237
+8.834177	-0.011970	0.014364	9.758119	0.047297	0.087000	-0.038504
+8.835152	0.028729	-0.040699	9.810788	0.047697	0.088332	-0.036372
+8.836161	0.035911	-0.014364	9.817970	0.049029	0.088199	-0.036239
+8.837194	0.014364	0.019152	9.837123	0.049429	0.087133	-0.034374
+8.838189	0.033517	0.016758	9.827546	0.047031	0.086467	-0.035306
+8.839154	0.052669	-0.002394	9.774877	0.044899	0.085934	-0.037704
+8.840176	0.038305	-0.057457	9.758119	0.044366	0.087133	-0.037704
+8.841195	0.009576	-0.086186	9.760513	0.047697	0.088998	-0.035306
+8.842195	0.002394	-0.038305	9.779666	0.048496	0.088199	-0.035306
+8.843195	-0.019152	0.004788	9.820364	0.046364	0.089132	-0.034907
+8.844194	0.050275	-0.026334	9.779666	0.045299	0.087799	-0.034773
+8.845194	0.035911	-0.014364	9.782060	0.043833	0.088599	-0.036239
+8.846195	0.026334	0.023940	9.815576	0.043966	0.088865	-0.034640
+8.847194	-0.009576	0.016758	9.865851	0.045565	0.087666	-0.034507
+8.848194	0.016758	-0.016758	9.822758	0.047963	0.087933	-0.035972
+8.849164	0.040699	-0.007182	9.762907	0.048896	0.088066	-0.036905
+8.850127	0.016758	0.009576	9.691086	0.047830	0.087799	-0.037971
+8.851119	-0.028729	0.045487	9.837123	0.047031	0.087933	-0.037305
+8.852187	-0.011970	0.019152	9.844305	0.047297	0.087666	-0.034507
+8.853195	-0.002394	-0.028729	9.770089	0.048896	0.088066	-0.035839
+8.854194	0.026334	-0.016758	9.779666	0.047564	0.088599	-0.036372
+8.855194	0.023940	-0.019152	9.762907	0.046498	0.088466	-0.037838
+8.856195	0.064639	0.007182	9.834729	0.047164	0.089132	-0.037838
+8.857151	0.000000	0.000000	9.849093	0.048230	0.089931	-0.034640
+8.858132	0.043093	0.009576	9.794030	0.047297	0.089531	-0.037438
+8.859142	0.040699	-0.031123	9.801212	0.046364	0.088732	-0.037438
+8.860184	-0.014364	0.028729	9.813182	0.046764	0.088865	-0.035839
+8.861190	-0.011970	0.035911	9.770089	0.046897	0.087933	-0.034507
+8.862196	-0.052669	-0.016758	9.719814	0.048096	0.088332	-0.035972
+8.863193	-0.062245	0.019152	9.829940	0.047564	0.088332	-0.038371
+8.864194	-0.004788	-0.040699	9.827546	0.046098	0.089265	-0.038770
+8.865196	0.062245	-0.040699	9.710238	0.046231	0.087799	-0.038637
+8.866196	0.004788	-0.016758	9.753331	0.046897	0.086334	-0.036639
+8.867192	-0.055063	-0.045487	9.741361	0.045299	0.089132	-0.035440
+8.868144	-0.011970	-0.040699	9.789242	0.045565	0.091930	-0.036772
+8.869188	0.052669	-0.009576	9.837123	0.045299	0.088865	-0.039436
+8.870146	0.007182	0.004788	9.772483	0.046098	0.087666	-0.037438
+8.871216	0.035911	0.011970	9.806000	0.046631	0.086467	-0.033841
+8.872194	0.002394	0.007182	9.767695	0.047430	0.087133	-0.034107
+8.873166	-0.009576	-0.028729	9.729391	0.049162	0.086600	-0.039303
+8.874195	-0.007182	-0.045487	9.808394	0.047564	0.087666	-0.039570
+8.875193	0.009576	0.014364	9.808394	0.049296	0.088599	-0.035306
+8.876192	0.033517	0.007182	9.779666	0.049029	0.088732	-0.036905
+8.877192	-0.028729	-0.031123	9.796424	0.047830	0.089398	-0.039170
+8.878195	-0.009576	0.016758	9.841911	0.047430	0.088998	-0.037305
+8.879191	0.002394	-0.026334	9.817970	0.045432	0.086467	-0.035839
+8.880172	0.009576	-0.067033	9.810788	0.044766	0.088732	-0.035573
+8.881189	0.004788	-0.043093	9.820364	0.047697	0.089531	-0.035306
+8.882194	-0.040699	0.067033	9.868245	0.048496	0.089531	-0.035839
+8.883191	0.026334	-0.035911	9.856275	0.045698	0.087799	-0.032642
+8.884124	-0.021546	0.004788	9.755725	0.045032	0.088199	-0.035839
+8.885162	-0.023940	-0.040699	9.810788	0.046498	0.089132	-0.038904
+8.886196	0.002394	-0.004788	9.861063	0.046498	0.089132	-0.037704
+8.887195	0.000000	-0.026334	9.861063	0.046364	0.087666	-0.036239
+8.888152	-0.028729	-0.004788	9.738967	0.045698	0.084868	-0.037438
+8.889197	-0.011970	-0.011970	9.858669	0.046764	0.084202	-0.036239
+8.890156	0.002394	-0.055063	9.894580	0.046498	0.085801	-0.034773
+8.891162	-0.004788	-0.055063	9.846699	0.044100	0.087133	-0.034907
+8.892189	0.002394	-0.033517	9.722208	0.043034	0.087799	-0.036106
+8.893194	-0.040699	-0.100550	9.715026	0.045432	0.087799	-0.038904
+8.894195	-0.021546	-0.038305	9.762907	0.047164	0.088199	-0.039436
+8.895193	0.038305	0.028729	9.789242	0.047430	0.087666	-0.034907
+8.896139	0.059851	0.004788	9.786848	0.047830	0.086867	-0.036505
+8.897194	0.055063	0.004788	9.794030	0.047430	0.089265	-0.037038
+8.898182	0.050275	0.026334	9.779666	0.046498	0.091397	-0.036639
+8.899194	0.007182	-0.011970	9.743755	0.046897	0.088466	-0.038237
+8.900193	-0.014364	-0.031123	9.789242	0.046631	0.086867	-0.036639
+8.901189	0.016758	0.002394	9.825152	0.046498	0.085934	-0.035173
+8.902220	0.021546	0.021546	9.846699	0.048363	0.083936	-0.036239
+8.903194	-0.011970	0.007182	9.801212	0.047697	0.086201	-0.036106
+8.904161	0.040699	-0.016758	9.786848	0.047830	0.088332	-0.033708
+8.905193	0.052669	-0.033517	9.743755	0.045165	0.088599	-0.033574
+8.906186	0.026334	-0.016758	9.794030	0.043433	0.087000	-0.036239
+8.907191	-0.059851	-0.004788	9.794030	0.046764	0.086867	-0.040502
+8.908150	-0.021546	0.007182	9.736573	0.048496	0.086734	-0.036372
+8.909188	0.007182	-0.055063	9.810788	0.047963	0.088998	-0.033574
+8.910202	-0.007182	0.002394	9.839517	0.048363	0.089665	-0.034907
+8.911151	0.000000	0.031123	9.777271	0.047830	0.088998	-0.037172
+8.912189	0.019152	-0.023940	9.774877	0.045698	0.089531	-0.037571
+8.913193	0.059851	-0.002394	9.784454	0.046098	0.087666	-0.037038
+8.914190	-0.028729	0.009576	9.794030	0.049429	0.087933	-0.034773
+8.915194	-0.028729	-0.007182	9.791636	0.051028	0.086067	-0.034640
+8.916191	0.038305	-0.023940	9.695874	0.050228	0.086600	-0.036639
+8.917129	-0.019152	-0.040699	9.770089	0.046231	0.086734	-0.035839
+8.918092	-0.026334	-0.016758	9.741361	0.045965	0.087933	-0.035173
+8.919107	0.055063	0.033517	9.794030	0.047164	0.086734	-0.036772
+8.920100	-0.035911	0.035911	9.813182	0.048096	0.085934	-0.036106
+8.921193	-0.035911	-0.047881	9.873033	0.048763	0.085934	-0.033708
+8.922164	-0.009576	-0.014364	9.861063	0.049029	0.087533	-0.033841
+8.923189	0.028729	-0.016758	9.765301	0.045032	0.087933	-0.034107
+8.924194	0.007182	-0.019152	9.724603	0.044366	0.087666	-0.036505
+8.925193	0.011970	0.009576	9.825152	0.046231	0.089398	-0.033841
+8.926190	-0.014364	0.009576	9.803606	0.045432	0.088332	-0.037838
+8.927193	0.023940	0.038305	9.806000	0.048096	0.085801	-0.039170
+8.928193	0.002394	-0.023940	9.853881	0.049429	0.087133	-0.035972
+8.929193	-0.035911	-0.038305	9.858669	0.050228	0.086467	-0.035173
+8.930188	0.004788	-0.011970	9.777271	0.049162	0.086201	-0.033841
+8.931162	0.000000	-0.011970	9.801212	0.045832	0.087133	-0.036905
+8.932181	-0.007182	0.002394	9.882609	0.046364	0.088199	-0.039436
+8.933195	-0.059851	-0.040699	9.813182	0.047830	0.089665	-0.035706
+8.934185	0.014364	-0.026334	9.803606	0.045432	0.087799	-0.038104
+8.935177	0.050275	-0.028729	9.743755	0.044632	0.086467	-0.038237
+8.936157	0.045487	-0.026334	9.846699	0.047564	0.085534	-0.037038
+8.937159	0.079003	0.007182	9.928096	0.048096	0.086600	-0.037172
+8.938161	0.035911	-0.069427	9.858669	0.046364	0.088599	-0.036106
+8.939153	0.000000	-0.062245	9.755725	0.047031	0.089132	-0.036106
+8.940156	0.004788	0.021546	9.738967	0.047031	0.088332	-0.037305
+8.941161	-0.026334	0.031123	9.765301	0.047564	0.089665	-0.036239
+8.942185	0.031123	0.059851	9.794030	0.048629	0.090198	-0.034240
+8.943184	-0.002394	0.028729	9.896974	0.046764	0.087933	-0.036505
+8.944247	0.007182	0.009576	9.863457	0.045299	0.086467	-0.037172
+8.945183	0.011970	0.016758	9.806000	0.044499	0.087799	-0.037704
+8.946186	0.016758	0.023940	9.750937	0.045832	0.088199	-0.035706
+8.947177	-0.021546	-0.011970	9.722208	0.047963	0.087933	-0.034640
+8.948195	-0.031123	-0.002394	9.717420	0.049828	0.087933	-0.036639
+8.949243	0.004788	0.004788	9.798818	0.046897	0.087400	-0.036505
+8.950246	-0.023940	-0.028729	9.853881	0.044499	0.088599	-0.034907
+8.951244	0.016758	0.000000	9.794030	0.043034	0.087266	-0.036372
+8.952178	-0.002394	0.014364	9.748543	0.043034	0.087933	-0.035173
+8.953206	-0.002394	-0.014364	9.791636	0.046364	0.086867	-0.033041
+8.954246	-0.007182	-0.047881	9.810788	0.046631	0.087533	-0.035972
+8.955245	0.043093	0.021546	9.825152	0.047697	0.085401	-0.037838
+8.956245	0.016758	0.002394	9.796424	0.047430	0.085668	-0.037305
+8.957198	0.014364	0.014364	9.760513	0.046364	0.084868	-0.037172
+8.958246	0.021546	0.021546	9.743755	0.048230	0.086201	-0.038104
+8.959244	0.035911	0.021546	9.755725	0.049429	0.088199	-0.036106
+8.960258	-0.011970	0.016758	9.817970	0.049029	0.090198	-0.037172
+8.961204	0.023940	-0.026334	9.911338	0.047697	0.090331	-0.038637
+8.962176	-0.002394	0.016758	9.810788	0.046764	0.088066	-0.036106
+8.963238	0.016758	0.028729	9.717420	0.047564	0.086734	-0.035839
+8.964244	0.033517	0.014364	9.724603	0.047697	0.087666	-0.035706
+8.965242	0.000000	-0.028729	9.810788	0.049296	0.086334	-0.035706
+8.966194	0.021546	-0.004788	9.817970	0.051560	0.087133	-0.035173
+8.967244	-0.011970	-0.043093	9.791636	0.049029	0.088466	-0.035040
+8.968192	0.007182	-0.035911	9.798818	0.046631	0.087533	-0.038104
+8.969189	0.035911	-0.009576	9.724603	0.047031	0.086600	-0.037704
+8.970210	-0.033517	-0.014364	9.762907	0.048363	0.089265	-0.035306
+8.971199	-0.031123	-0.067033	9.899368	0.047430	0.088732	-0.035040
+8.972249	0.045487	0.000000	9.892186	0.047164	0.090064	-0.038770
+8.973244	0.038305	-0.028729	9.873033	0.047031	0.089531	-0.040502
+8.974248	0.009576	0.000000	9.817970	0.047963	0.089665	-0.037438
+8.975244	0.000000	-0.062245	9.832334	0.047430	0.092729	-0.034773
+8.976244	-0.035911	-0.064639	9.885003	0.047697	0.091397	-0.036639
+8.977244	0.004788	-0.062245	9.837123	0.048230	0.089132	-0.037838
+8.978244	0.011970	-0.033517	9.789242	0.048629	0.086867	-0.039170
+8.979197	-0.014364	-0.016758	9.789242	0.047164	0.085002	-0.034107
+8.980233	0.014364	-0.031123	9.700662	0.044632	0.086201	-0.035972
+8.981238	0.050275	-0.038305	9.801212	0.045832	0.090864	-0.035706
+8.982182	0.038305	-0.019152	9.820364	0.047031	0.091397	-0.036372
+8.983187	-0.004788	0.035911	9.758119	0.046498	0.089398	-0.036772
+8.984173	0.045487	0.011970	9.717420	0.046231	0.087933	-0.037838
+8.985133	0.052669	-0.028729	9.796424	0.043300	0.088332	-0.036106
+8.986175	0.004788	0.002394	9.825152	0.043567	0.087000	-0.032375
+8.987188	0.031123	-0.004788	9.822758	0.046498	0.087933	-0.033041
+8.988170	0.028729	0.055063	9.801212	0.047830	0.087533	-0.034374
+8.989171	0.009576	0.043093	9.746149	0.048763	0.086600	-0.032642
+8.990102	0.019152	-0.014364	9.827546	0.049162	0.088466	-0.033841
+8.991097	-0.052669	-0.016758	9.825152	0.047564	0.088998	-0.035040
+8.992129	-0.031123	-0.004788	9.791636	0.047031	0.088599	-0.036106
+8.993170	-0.004788	-0.004788	9.877821	0.047164	0.088865	-0.037438
+8.994178	-0.007182	0.102944	9.961613	0.045832	0.088865	-0.038504
+8.995185	-0.002394	0.028729	9.863457	0.043567	0.087133	-0.035972
+8.996184	-0.050275	-0.002394	9.846699	0.043433	0.086867	-0.034240
+8.997183	-0.064639	0.000000	9.849093	0.045299	0.087933	-0.036106
+8.998109	-0.014364	-0.021546	9.806000	0.046498	0.086467	-0.037704
+8.999108	0.033517	-0.052669	9.738967	0.047564	0.086734	-0.040769
+9.000183	-0.004788	-0.050275	9.755725	0.047830	0.088865	-0.039969
+9.001191	-0.019152	0.033517	9.806000	0.047430	0.088998	-0.037838
+9.002109	0.019152	0.023940	9.810788	0.045165	0.088332	-0.036505
+9.003204	0.023940	-0.007182	9.782060	0.045698	0.088599	-0.038237
+9.004186	-0.023940	-0.009576	9.791636	0.048230	0.089798	-0.035040
+9.005186	0.016758	-0.011970	9.858669	0.046631	0.087400	-0.035440
+9.006186	0.031123	-0.035911	9.827546	0.045165	0.086467	-0.038371
+9.007166	-0.004788	-0.019152	9.777271	0.046364	0.088998	-0.036639
+9.008186	-0.050275	0.033517	9.743755	0.048096	0.089665	-0.036372
+9.009140	0.021546	0.031123	9.722208	0.048096	0.087533	-0.038904
+9.010102	0.052669	-0.026334	9.777271	0.047830	0.087133	-0.037172
+9.011119	0.011970	-0.026334	9.832334	0.045432	0.091397	-0.037838
+9.012120	0.000000	-0.031123	9.765301	0.045432	0.092862	-0.038904
+9.013102	-0.011970	-0.011970	9.736573	0.045832	0.089798	-0.040769
+9.014143	0.002394	-0.007182	9.679116	0.045698	0.086201	-0.041835
+9.015185	-0.007182	-0.011970	9.832334	0.045965	0.086734	-0.036372
+9.016124	0.004788	-0.007182	9.820364	0.044766	0.087799	-0.034773
+9.017109	0.009576	-0.050275	9.736573	0.048363	0.087799	-0.036639
+9.018094	-0.014364	-0.002394	9.834729	0.049296	0.089265	-0.037038
+9.019113	-0.028729	-0.002394	9.916126	0.046098	0.088466	-0.038770
+9.020135	-0.035911	-0.004788	9.863457	0.045165	0.087533	-0.035972
+9.021182	-0.040699	0.033517	9.911338	0.044366	0.088732	-0.035173
+9.022185	-0.011970	0.014364	9.801212	0.044233	0.087266	-0.035306
+9.023186	-0.011970	-0.021546	9.765301	0.047031	0.085801	-0.037704
+9.024179	-0.014364	-0.026334	9.734179	0.048230	0.085668	-0.037038
+9.025164	-0.019152	-0.009576	9.736573	0.046631	0.086734	-0.037838
+9.026184	-0.007182	0.009576	9.760513	0.045965	0.086467	-0.039303
+9.027182	-0.014364	0.009576	9.789242	0.048096	0.088332	-0.038504
+9.028184	0.009576	-0.035911	9.707844	0.045698	0.087000	-0.035839
+9.029186	-0.021546	-0.050275	9.760513	0.047564	0.084735	-0.037838
+9.030185	-0.057457	-0.004788	9.844305	0.048763	0.083936	-0.035839
+9.031184	0.011970	0.016758	9.849093	0.047564	0.086467	-0.036905
+9.032157	-0.011970	-0.011970	9.837123	0.046364	0.090198	-0.036372
+9.033181	-0.014364	-0.052669	9.772483	0.045698	0.090464	-0.037571
+9.034189	0.052669	-0.043093	9.715026	0.047031	0.089931	-0.037438
+9.035165	0.016758	0.000000	9.825152	0.050095	0.091796	-0.033574
+9.036183	0.026334	-0.011970	9.789242	0.051560	0.092329	-0.030110
+9.037182	0.016758	-0.033517	9.786848	0.048096	0.087666	-0.033175
+9.038188	0.019152	0.016758	9.779666	0.047031	0.086201	-0.036905
+9.039182	0.033517	0.031123	9.853881	0.048230	0.089132	-0.037038
+9.040185	0.002394	0.014364	9.889792	0.047430	0.089665	-0.037038
+9.041130	0.023940	-0.019152	9.896974	0.047830	0.085934	-0.037571
+9.042121	0.069427	0.009576	9.834729	0.049828	0.087266	-0.037305
+9.043140	0.016758	0.009576	9.767695	0.049562	0.088998	-0.035573
+9.044163	0.007182	0.009576	9.777271	0.046764	0.090464	-0.035173
+9.045171	0.040699	-0.007182	9.750937	0.045832	0.088732	-0.037971
+9.046185	-0.026334	-0.055063	9.817970	0.046764	0.087400	-0.035839
+9.047180	0.009576	-0.028729	9.873033	0.047297	0.088066	-0.035173
+9.048185	0.055063	-0.038305	9.798818	0.047031	0.088732	-0.032775
+9.049183	0.031123	-0.026334	9.820364	0.047164	0.087933	-0.033708
+9.050195	0.076609	-0.031123	9.779666	0.047430	0.086600	-0.037038
+9.051244	0.019152	-0.026334	9.770089	0.046631	0.086334	-0.039303
+9.052180	0.021546	-0.002394	9.868245	0.050361	0.088732	-0.035173
+9.053244	0.026334	-0.028729	9.832334	0.048363	0.087000	-0.034374
+9.054200	-0.019152	0.004788	9.863457	0.046364	0.087533	-0.034507
+9.055239	-0.043093	-0.035911	9.762907	0.047963	0.088466	-0.032908
+9.056245	0.011970	-0.045487	9.784454	0.050095	0.089531	-0.033041
+9.057222	0.004788	0.043093	9.801212	0.049162	0.086734	-0.034240
+9.058248	0.043093	0.038305	9.815576	0.047564	0.086067	-0.032775
+9.059197	0.055063	-0.009576	9.820364	0.045432	0.087533	-0.032508
+9.060200	0.040699	-0.021546	9.815576	0.045565	0.084735	-0.032109
+9.061241	0.045487	-0.033517	9.841911	0.046764	0.086334	-0.034640
+9.062212	0.021546	-0.045487	9.810788	0.048096	0.088466	-0.036239
+9.063199	0.011970	-0.043093	9.810788	0.047297	0.088199	-0.040103
+9.064243	-0.019152	-0.014364	9.736573	0.045698	0.088865	-0.037971
+9.065245	-0.009576	-0.047881	9.782060	0.048096	0.089931	-0.034773
+9.066248	0.000000	-0.067033	9.784454	0.048363	0.091263	-0.035972
+9.067173	0.009576	0.011970	9.822758	0.047031	0.090597	-0.036372
+9.068177	-0.011970	-0.014364	9.863457	0.047963	0.088466	-0.036372
+9.069245	0.033517	-0.019152	9.885003	0.048096	0.084868	-0.035440
+9.070187	0.043093	-0.014364	9.748543	0.048096	0.086067	-0.037571
+9.071243	-0.004788	-0.007182	9.779666	0.045565	0.089798	-0.034640
+9.072183	0.014364	-0.047881	9.863457	0.045032	0.089931	-0.034773
+9.073233	-0.019152	-0.002394	9.827546	0.046764	0.088199	-0.034374
+9.074247	-0.057457	0.043093	9.803606	0.047430	0.088466	-0.036772
+9.075255	-0.038305	-0.023940	9.808394	0.045165	0.088732	-0.036372
+9.076245	-0.021546	-0.033517	9.832334	0.045432	0.088199	-0.034374
+9.077244	-0.011970	-0.011970	9.784454	0.047697	0.086334	-0.034240
+9.078246	-0.040699	0.002394	9.703056	0.047963	0.083936	-0.034240
+9.079181	0.002394	-0.052669	9.762907	0.048496	0.085934	-0.035306
+9.080162	0.009576	-0.045487	9.717420	0.047830	0.088599	-0.040502
+9.081199	0.007182	-0.028729	9.806000	0.044899	0.087666	-0.040236
+9.082239	0.043093	0.000000	9.772483	0.045032	0.087933	-0.037438
+9.083243	0.004788	0.011970	9.746149	0.047564	0.089665	-0.036639
+9.084245	0.016758	0.004788	9.815576	0.047963	0.090198	-0.038237
+9.085157	0.031123	0.000000	9.770089	0.049029	0.088865	-0.036106
+9.086200	0.031123	0.026334	9.789242	0.046498	0.085934	-0.037038
+9.087179	0.007182	0.040699	9.822758	0.043966	0.085534	-0.040369
+9.088172	0.028729	0.033517	9.839517	0.044632	0.085534	-0.037838
+9.089244	0.035911	0.035911	9.856275	0.046498	0.086467	-0.036106
+9.090242	-0.002394	0.014364	9.853881	0.049162	0.088732	-0.035306
+9.091197	0.004788	-0.019152	9.856275	0.048230	0.087400	-0.036106
+9.092240	-0.019152	0.004788	9.770089	0.046098	0.088199	-0.035839
+9.093184	0.004788	-0.004788	9.779666	0.045432	0.089531	-0.033574
+9.094246	0.019152	-0.014364	9.779666	0.044366	0.089931	-0.035839
+9.095242	0.052669	-0.033517	9.849093	0.045965	0.092462	-0.037438
+9.096243	0.026334	-0.009576	9.791636	0.048230	0.093528	-0.035440
+9.097245	0.055063	-0.031123	9.786848	0.048763	0.090864	-0.035173
+9.098165	-0.019152	0.002394	9.813182	0.046364	0.087933	-0.037438
+9.099215	-0.033517	-0.014364	9.806000	0.047164	0.085268	-0.038371
+9.100200	0.000000	0.031123	9.801212	0.045965	0.085002	-0.036505
+9.101196	0.023940	0.031123	9.865851	0.046631	0.085534	-0.037838
+9.102251	-0.016758	0.081397	9.798818	0.046631	0.087666	-0.037305
+9.103241	0.002394	0.009576	9.794030	0.047564	0.086334	-0.035706
+9.104243	0.045487	0.011970	9.753331	0.049695	0.087400	-0.036905
+9.105205	0.067033	-0.033517	9.796424	0.047564	0.090464	-0.035972
+9.106246	0.067033	-0.081397	9.801212	0.045032	0.090597	-0.038237
+9.107159	0.043093	0.014364	9.772483	0.046098	0.087133	-0.037038
+9.108167	0.026334	-0.014364	9.820364	0.047164	0.085135	-0.037971
+9.109186	0.007182	-0.045487	9.894580	0.048496	0.088199	-0.037571
+9.110201	-0.021546	-0.014364	9.777271	0.048096	0.090864	-0.036239
+9.111239	-0.038305	0.045487	9.837123	0.045965	0.090864	-0.037571
+9.112243	-0.064639	0.062245	9.841911	0.043700	0.087266	-0.037438
+9.113243	0.028729	-0.007182	9.853881	0.043034	0.085002	-0.035706
+9.114246	0.043093	-0.011970	9.777271	0.046098	0.087933	-0.034907
+9.115241	0.019152	-0.043093	9.798818	0.047830	0.087666	-0.036772
+9.116241	-0.033517	-0.014364	9.820364	0.047697	0.089265	-0.037038
+9.117242	-0.028729	0.000000	9.853881	0.049162	0.090464	-0.037838
+9.118170	-0.019152	-0.009576	9.806000	0.047963	0.086334	-0.034240
+9.119182	0.026334	-0.023940	9.815576	0.047164	0.084868	-0.037305
+9.120208	0.033517	-0.021546	9.856275	0.046764	0.086867	-0.037971
+9.121243	0.000000	-0.026334	9.858669	0.046631	0.087666	-0.040103
+9.122247	-0.009576	-0.016758	9.748543	0.049162	0.087933	-0.041435
+9.123242	0.016758	-0.038305	9.820364	0.048096	0.088332	-0.040902
+9.124242	0.045487	-0.019152	9.772483	0.047963	0.087400	-0.038371
+9.125182	0.052669	-0.050275	9.829940	0.049562	0.087933	-0.038637
+9.126242	0.040699	-0.055063	9.803606	0.050095	0.089265	-0.037971
+9.127198	0.045487	-0.021546	9.868245	0.047164	0.087533	-0.036905
+9.128209	-0.014364	-0.043093	9.865851	0.046498	0.087400	-0.036372
+9.129243	0.000000	0.016758	9.777271	0.046764	0.086600	-0.036905
+9.130246	0.045487	0.031123	9.717420	0.047297	0.087000	-0.038904
+9.131242	0.031123	0.002394	9.782060	0.048629	0.089531	-0.037172
+9.132242	0.026334	0.031123	9.789242	0.047963	0.090997	-0.035173
+9.133242	-0.023940	-0.019152	9.817970	0.048629	0.090597	-0.035040
+9.134206	-0.071821	-0.033517	9.750937	0.047297	0.090997	-0.036106
+9.135177	-0.011970	-0.031123	9.813182	0.045432	0.089665	-0.034240
+9.136197	-0.014364	-0.050275	9.796424	0.047164	0.090198	-0.035573
+9.137181	0.014364	-0.004788	9.808394	0.046231	0.087400	-0.038770
+9.138241	0.002394	0.007182	9.837123	0.047031	0.087400	-0.035706
+9.139192	-0.026334	-0.023940	9.865851	0.048763	0.087533	-0.033175
+9.140245	-0.014364	-0.011970	9.829940	0.046631	0.087533	-0.030243
+9.141243	-0.007182	-0.014364	9.784454	0.044632	0.087000	-0.033841
+9.142248	0.028729	-0.028729	9.782060	0.047697	0.088066	-0.034507
+9.143244	0.045487	-0.021546	9.784454	0.047430	0.091263	-0.036639
+9.144241	-0.026334	0.079003	9.777271	0.046631	0.092329	-0.039836
+9.145202	-0.014364	-0.043093	9.767695	0.046498	0.090464	-0.039703
+9.146239	0.002394	-0.052669	9.750937	0.049162	0.088466	-0.036372
+9.147242	0.007182	-0.016758	9.782060	0.047830	0.088998	-0.035440
+9.148165	0.033517	-0.035911	9.841911	0.046631	0.089265	-0.036239
+9.149217	0.023940	0.031123	9.868245	0.046231	0.089265	-0.037838
+9.150203	0.004788	0.016758	9.791636	0.044366	0.088199	-0.035440
+9.151172	0.002394	-0.040699	9.753331	0.043966	0.086867	-0.035306
+9.152146	-0.057457	-0.011970	9.760513	0.043167	0.087400	-0.035040
+9.153142	0.011970	-0.002394	9.734179	0.046098	0.088199	-0.035706
+9.154173	0.035911	-0.057457	9.774877	0.049429	0.087933	-0.035706
+9.155159	0.011970	-0.009576	9.925702	0.047164	0.087533	-0.034907
+9.156167	0.026334	0.026334	9.911338	0.046231	0.089398	-0.039836
+9.157131	0.050275	0.014364	9.841911	0.047564	0.085668	-0.039170
+9.158136	0.023940	0.007182	9.827546	0.047031	0.084602	-0.035573
+9.159138	-0.021546	0.000000	9.770089	0.050095	0.085534	-0.033574
+9.160152	0.019152	-0.028729	9.817970	0.051028	0.087933	-0.034374
+9.161154	0.038305	-0.047881	9.798818	0.047564	0.087533	-0.035173
+9.162141	0.033517	-0.014364	9.703056	0.045832	0.083536	-0.033974
+9.163140	0.026334	-0.014364	9.753331	0.046231	0.084868	-0.034907
+9.164134	0.002394	-0.038305	9.841911	0.045299	0.087666	-0.038504
+9.165138	-0.007182	-0.028729	9.829940	0.045432	0.091263	-0.036905
+9.166139	0.014364	-0.019152	9.894580	0.047830	0.092729	-0.040236
+9.167135	0.000000	0.035911	9.784454	0.051294	0.089398	-0.039570
+9.168140	-0.011970	0.033517	9.782060	0.050228	0.088199	-0.035440
+9.169139	-0.035911	-0.011970	9.817970	0.046631	0.086067	-0.031975
+9.170083	-0.059851	-0.026334	9.817970	0.044499	0.083936	-0.035972
+9.171084	-0.004788	-0.004788	9.846699	0.049695	0.086867	-0.036505
+9.172083	-0.026334	-0.019152	9.820364	0.048363	0.088066	-0.037305
+9.173080	0.047881	-0.050275	9.858669	0.045032	0.087133	-0.036372
+9.174081	0.004788	-0.007182	9.798818	0.045565	0.083936	-0.037038
+9.175082	-0.031123	0.040699	9.817970	0.046764	0.086067	-0.034907
+9.176104	-0.007182	0.011970	9.801212	0.046764	0.087666	-0.031842
+9.177093	0.023940	-0.016758	9.820364	0.047031	0.090064	-0.035706
+9.178087	0.002394	-0.038305	9.803606	0.048496	0.090730	-0.035173
+9.179096	0.021546	-0.009576	9.825152	0.048496	0.088466	-0.035839
+9.180093	0.062245	0.023940	9.858669	0.046764	0.087133	-0.037971
+9.181091	-0.004788	-0.035911	9.810788	0.046498	0.087933	-0.036505
+9.182116	0.014364	-0.021546	9.750937	0.045032	0.089398	-0.034907
+9.183107	-0.026334	-0.050275	9.734179	0.045965	0.089798	-0.034240
+9.184101	0.026334	-0.047881	9.774877	0.048363	0.089798	-0.037172
+9.185100	0.019152	-0.040699	9.791636	0.047830	0.087266	-0.038904
+9.186123	0.026334	-0.019152	9.784454	0.048629	0.085002	-0.038104
+9.187120	0.062245	-0.040699	9.715026	0.047164	0.084202	-0.037172
+9.188102	0.052669	-0.081397	9.746149	0.047031	0.086867	-0.035440
+9.189112	0.047881	-0.071821	9.717420	0.046764	0.088865	-0.035306
+9.190112	0.040699	-0.026334	9.803606	0.048363	0.088732	-0.034773
+9.191122	0.040699	-0.014364	9.820364	0.047963	0.086600	-0.036239
+9.192120	0.026334	0.002394	9.753331	0.047297	0.084735	-0.037571
+9.193104	0.057457	-0.100550	9.796424	0.048363	0.085268	-0.037571
+9.194165	-0.067033	-0.057457	9.789242	0.049162	0.086600	-0.035839
+9.195160	-0.007182	-0.011970	9.817970	0.046364	0.088466	-0.033974
+9.196147	-0.004788	0.038305	9.767695	0.043700	0.089798	-0.033708
+9.197167	0.009576	0.040699	9.808394	0.045165	0.088199	-0.033708
+9.198104	0.074215	0.002394	9.853881	0.047830	0.087133	-0.035173
+9.199103	0.100550	-0.050275	9.877821	0.046098	0.086067	-0.036905
+9.200103	0.009576	-0.038305	9.901762	0.044632	0.085801	-0.035839
+9.201102	0.028729	0.019152	9.791636	0.045965	0.086734	-0.036372
+9.202098	0.011970	0.004788	9.791636	0.048363	0.088732	-0.036106
+9.203105	0.014364	-0.033517	9.789242	0.048363	0.089798	-0.036372
+9.204104	0.011970	0.033517	9.786848	0.047430	0.086734	-0.038637
+9.205095	-0.002394	0.040699	9.746149	0.045965	0.086734	-0.038637
+9.206095	-0.007182	0.004788	9.810788	0.048363	0.087000	-0.037971
+9.207094	0.033517	-0.021546	9.865851	0.048629	0.085534	-0.034374
+9.208099	0.035911	-0.016758	9.952037	0.048629	0.086334	-0.031842
+9.209099	0.021546	0.000000	9.858669	0.047963	0.088199	-0.034773
+9.210098	-0.009576	-0.014364	9.858669	0.047697	0.089931	-0.037038
+9.211094	-0.021546	-0.026334	9.777271	0.047297	0.087400	-0.036505
+9.212099	-0.014364	0.002394	9.779666	0.046364	0.087133	-0.036372
+9.213102	0.009576	-0.002394	9.815576	0.048363	0.087533	-0.034907
+9.214129	0.057457	-0.026334	9.770089	0.049296	0.086467	-0.035706
+9.215181	0.026334	0.004788	9.786848	0.048629	0.087400	-0.035706
+9.216179	-0.014364	0.038305	9.782060	0.049029	0.087799	-0.036106
+9.217136	0.004788	0.043093	9.770089	0.048629	0.089398	-0.036905
+9.218142	0.000000	0.021546	9.813182	0.047564	0.089531	-0.038504
+9.219147	-0.019152	0.019152	9.806000	0.046764	0.088998	-0.036239
+9.220182	-0.002394	-0.009576	9.853881	0.046631	0.088332	-0.035440
+9.221134	-0.031123	-0.021546	9.798818	0.045299	0.089265	-0.035839
+9.222142	0.007182	0.028729	9.810788	0.046897	0.088998	-0.037038
+9.223125	-0.004788	0.023940	9.827546	0.046364	0.088865	-0.034907
+9.224118	0.007182	-0.004788	9.870639	0.044632	0.091263	-0.036239
+9.225139	0.014364	-0.021546	9.767695	0.047830	0.088732	-0.035173
+9.226151	0.014364	-0.002394	9.832334	0.049695	0.085534	-0.034374
+9.227180	-0.004788	-0.004788	9.844305	0.047564	0.085668	-0.037172
+9.228179	0.069427	0.002394	9.738967	0.047164	0.087933	-0.037172
+9.229132	0.009576	0.007182	9.765301	0.047830	0.088599	-0.033708
+9.230117	0.004788	0.014364	9.738967	0.047164	0.087266	-0.032775
+9.231179	-0.014364	-0.019152	9.822758	0.047164	0.086467	-0.034240
+9.232174	-0.021546	-0.038305	9.853881	0.045432	0.088732	-0.035573
+9.233134	0.016758	-0.047881	9.777271	0.045032	0.088332	-0.035972
+9.234140	0.028729	0.007182	9.784454	0.047963	0.088066	-0.036772
+9.235112	0.023940	0.023940	9.777271	0.048496	0.086067	-0.037172
+9.236183	0.035911	-0.026334	9.786848	0.048363	0.083802	-0.038237
+9.237134	0.023940	0.007182	9.825152	0.048496	0.085934	-0.038637
+9.238177	0.004788	0.004788	9.782060	0.047697	0.089931	-0.036505
+9.239165	0.026334	0.016758	9.806000	0.048096	0.090198	-0.036106
+9.240179	0.035911	0.007182	9.746149	0.045299	0.091397	-0.037438
+9.241133	0.016758	0.028729	9.782060	0.044899	0.088066	-0.036239
+9.242180	-0.004788	-0.023940	9.755725	0.045299	0.087266	-0.035040
+9.243180	0.038305	0.021546	9.774877	0.046098	0.092196	-0.034773
+9.244180	0.031123	-0.004788	9.834729	0.045965	0.092196	-0.040103
+9.245115	-0.023940	0.026334	9.782060	0.045832	0.087666	-0.038904
+9.246200	-0.028729	-0.023940	9.755725	0.045965	0.085268	-0.036372
+9.247183	0.040699	0.016758	9.681510	0.047697	0.086867	-0.036772
+9.248124	0.035911	0.021546	9.719814	0.046631	0.087000	-0.036772
+9.249113	0.011970	0.007182	9.726997	0.046098	0.086334	-0.037971
+9.250100	0.011970	-0.011970	9.722208	0.046498	0.085534	-0.037838
+9.251177	0.023940	-0.019152	9.731785	0.048763	0.087133	-0.039570
+9.252182	0.004788	-0.033517	9.786848	0.050228	0.088865	-0.038904
+9.253174	0.009576	-0.074215	9.901762	0.047564	0.086334	-0.035972
+9.254181	0.009576	-0.026334	9.810788	0.045432	0.085934	-0.035306
+9.255181	-0.002394	-0.026334	9.750937	0.046231	0.087400	-0.037305
+9.256147	0.043093	-0.002394	9.834729	0.045698	0.087799	-0.036505
+9.257128	0.055063	-0.033517	9.880215	0.046764	0.087799	-0.039703
+9.258183	-0.002394	-0.047881	9.858669	0.047430	0.090064	-0.037571
+9.259179	-0.028729	0.002394	9.798818	0.047297	0.089132	-0.033175
+9.260093	-0.002394	-0.023940	9.794030	0.049296	0.086734	-0.034640
+9.261180	0.004788	-0.047881	9.798818	0.049429	0.087266	-0.037305
+9.262182	0.014364	0.004788	9.784454	0.049429	0.086067	-0.036639
+9.263179	-0.007182	0.002394	9.837123	0.047564	0.085534	-0.037704
+9.264180	-0.040699	0.004788	9.839517	0.047963	0.086600	-0.034773
+9.265182	-0.026334	-0.045487	9.794030	0.047564	0.086867	-0.035839
+9.266161	0.002394	-0.047881	9.794030	0.048629	0.088199	-0.038770
+9.267134	0.016758	0.021546	9.774877	0.046498	0.087400	-0.038637
+9.268142	-0.004788	-0.043093	9.743755	0.046231	0.090464	-0.034773
+9.269143	0.014364	-0.026334	9.808394	0.045965	0.090331	-0.035972
+9.270181	0.026334	-0.016758	9.808394	0.047963	0.089931	-0.037704
+9.271168	0.086186	0.007182	9.837123	0.046897	0.088466	-0.034507
+9.272181	0.088580	0.002394	9.765301	0.043833	0.091130	-0.031176
+9.273180	0.040699	-0.047881	9.789242	0.045565	0.090597	-0.034107
+9.274180	0.000000	-0.045487	9.822758	0.047164	0.088732	-0.035306
+9.275162	0.033517	-0.040699	9.829940	0.048629	0.087666	-0.033041
+9.276180	0.050275	-0.014364	9.803606	0.048763	0.089398	-0.034374
+9.277138	0.069427	0.009576	9.700662	0.046231	0.089398	-0.036772
+9.278127	0.055063	0.007182	9.813182	0.046364	0.089665	-0.035972
+9.279181	0.021546	-0.031123	9.767695	0.047430	0.088732	-0.035306
+9.280180	0.026334	-0.019152	9.782060	0.049029	0.088332	-0.036905
+9.281183	0.011970	0.040699	9.827546	0.047697	0.086867	-0.036772
+9.282184	0.016758	-0.019152	9.834729	0.045299	0.086201	-0.036772
+9.283180	0.045487	0.035911	9.767695	0.047031	0.088332	-0.036905
+9.284116	0.023940	-0.002394	9.832334	0.047963	0.091263	-0.035972
+9.285110	0.031123	0.007182	9.825152	0.048896	0.090597	-0.035972
+9.286105	-0.011970	0.002394	9.748543	0.048230	0.088199	-0.037571
+9.287098	0.014364	0.002394	9.707844	0.046897	0.085934	-0.036905
+9.288096	0.033517	0.023940	9.770089	0.044899	0.084868	-0.038904
+9.289150	-0.031123	0.043093	9.815576	0.044766	0.088066	-0.040236
+9.290139	-0.047881	0.007182	9.798818	0.044499	0.086867	-0.037571
+9.291082	-0.067033	-0.028729	9.851487	0.046364	0.086734	-0.033441
+9.292100	-0.079003	0.081397	9.762907	0.049695	0.087933	-0.031443
+9.293096	0.011970	0.074215	9.750937	0.047697	0.089265	-0.034773
+9.294118	0.004788	0.016758	9.837123	0.045299	0.086334	-0.036639
+9.295178	-0.016758	-0.059851	9.834729	0.045565	0.087666	-0.037305
+9.296101	-0.002394	0.000000	9.789242	0.046364	0.090331	-0.035173
+9.297135	0.031123	-0.033517	9.875427	0.048096	0.089798	-0.031576
+9.298101	0.052669	-0.011970	9.772483	0.048230	0.088332	-0.034107
+9.299102	0.035911	0.021546	9.724603	0.046897	0.089265	-0.035040
+9.300102	0.000000	0.026334	9.712632	0.047430	0.086600	-0.035972
+9.301102	-0.021546	-0.045487	9.803606	0.047430	0.086067	-0.037838
+9.302103	-0.033517	-0.007182	9.779666	0.047031	0.087666	-0.035040
+9.303102	0.016758	-0.007182	9.738967	0.047430	0.088599	-0.038237
+9.304118	0.011970	-0.026334	9.822758	0.047031	0.088066	-0.037305
+9.305126	0.035911	-0.023940	9.796424	0.046231	0.086467	-0.035040
+9.306093	0.031123	-0.023940	9.868245	0.047564	0.087799	-0.033574
+9.307176	0.040699	-0.021546	9.849093	0.047564	0.090464	-0.032242
+9.308140	0.050275	0.023940	9.841911	0.046897	0.090597	-0.034640
+9.309118	-0.007182	-0.023940	9.794030	0.046231	0.088599	-0.035573
+9.310133	0.035911	0.011970	9.825152	0.045965	0.088066	-0.031443
+9.311181	0.059851	0.007182	9.834729	0.045299	0.087400	-0.032642
+9.312181	-0.019152	-0.047881	9.870639	0.046231	0.087000	-0.035440
+9.313182	0.023940	0.007182	9.810788	0.049695	0.087666	-0.037571
+9.314162	-0.028729	0.067033	9.731785	0.046764	0.087266	-0.034907
+9.315202	0.004788	0.019152	9.738967	0.043567	0.084735	-0.033841
+9.316179	-0.007182	-0.033517	9.779666	0.046098	0.086334	-0.034374
+9.317124	0.007182	0.004788	9.753331	0.044899	0.087666	-0.037704
+9.318125	0.033517	-0.009576	9.810788	0.046631	0.088732	-0.038237
+9.319130	0.021546	-0.026334	9.791636	0.049296	0.088998	-0.036505
+9.320130	-0.007182	0.000000	9.679116	0.046498	0.087933	-0.037438
+9.321131	0.016758	0.016758	9.810788	0.044499	0.085401	-0.036905
+9.322130	0.016758	0.002394	9.837123	0.043833	0.086734	-0.035972
+9.323130	-0.007182	0.026334	9.851487	0.046364	0.087133	-0.033308
+9.324166	-0.007182	0.026334	9.813182	0.048496	0.089132	-0.039570
+9.325159	0.023940	0.052669	9.887397	0.046364	0.088332	-0.040236
+9.326149	0.011970	0.052669	9.889792	0.045965	0.086734	-0.035440
+9.327134	-0.007182	0.026334	9.794030	0.046098	0.086734	-0.035040
+9.328121	0.071821	0.009576	9.765301	0.048096	0.088865	-0.031309
+9.329180	0.031123	-0.014364	9.770089	0.048230	0.089398	-0.032642
+9.330111	0.050275	-0.014364	9.873033	0.049562	0.089531	-0.035440
+9.331116	0.028729	0.057457	9.851487	0.050495	0.089265	-0.035839
+9.332181	0.038305	0.055063	9.798818	0.045698	0.089398	-0.038104
+9.333180	0.040699	0.081397	9.750937	0.043700	0.089798	-0.039037
+9.334145	0.031123	0.043093	9.712632	0.045965	0.087266	-0.036639
+9.335107	0.038305	-0.031123	9.743755	0.045565	0.087533	-0.037038
+9.336176	0.050275	-0.021546	9.868245	0.044499	0.088732	-0.036905
+9.337162	0.040699	-0.031123	9.796424	0.045432	0.089398	-0.036772
+9.338121	0.016758	0.014364	9.779666	0.045565	0.088066	-0.037838
+9.339140	0.023940	-0.007182	9.839517	0.043567	0.085534	-0.036106
+9.340175	0.038305	-0.033517	9.794030	0.043433	0.086334	-0.036505
+9.341176	0.043093	0.011970	9.741361	0.047697	0.086067	-0.037971
+9.342181	0.009576	0.016758	9.779666	0.048896	0.087666	-0.037438
+9.343180	0.023940	0.019152	9.808394	0.047963	0.088599	-0.036905
+9.344180	0.038305	0.031123	9.779666	0.048629	0.089132	-0.038104
+9.345176	0.055063	0.055063	9.779666	0.048096	0.087799	-0.038770
+9.346182	0.016758	0.009576	9.779666	0.046631	0.085534	-0.036372
+9.347179	-0.011970	-0.067033	9.849093	0.046897	0.085401	-0.035173
+9.348149	-0.011970	-0.057457	9.837123	0.047564	0.087799	-0.035839
+9.349136	0.069427	-0.019152	9.856275	0.046364	0.087799	-0.037038
+9.350120	0.035911	-0.007182	9.815576	0.046364	0.088466	-0.035839
+9.351124	0.007182	0.000000	9.726997	0.047164	0.087000	-0.035440
+9.352075	-0.007182	0.016758	9.825152	0.047297	0.087133	-0.035173
+9.353082	0.021546	0.031123	9.820364	0.047430	0.087400	-0.034773
+9.354131	0.026334	-0.021546	9.837123	0.045832	0.086600	-0.036772
+9.355130	0.014364	-0.031123	9.822758	0.047164	0.087799	-0.037971
+9.356129	0.021546	-0.031123	9.748543	0.047031	0.089265	-0.037438
+9.357129	0.014364	0.028729	9.853881	0.047963	0.091130	-0.034907
+9.358131	-0.033517	0.033517	9.892186	0.047697	0.090597	-0.035706
+9.359130	0.009576	0.045487	9.868245	0.047697	0.088466	-0.037438
+9.360089	0.026334	0.019152	9.803606	0.047164	0.088466	-0.038770
+9.361130	0.026334	-0.009576	9.786848	0.045299	0.092995	-0.037305
+9.362134	0.004788	0.011970	9.832334	0.046098	0.091130	-0.035972
+9.363129	0.035911	-0.021546	9.844305	0.047830	0.088199	-0.035573
+9.364131	0.011970	0.016758	9.856275	0.043966	0.088599	-0.035440
+9.365131	0.016758	0.014364	9.777271	0.043833	0.091130	-0.033441
+9.366135	0.052669	-0.031123	9.829940	0.044766	0.090864	-0.034374
+9.367130	0.016758	0.014364	9.820364	0.047297	0.089665	-0.036905
+9.368100	0.009576	-0.033517	9.784454	0.048230	0.087799	-0.039436
+9.369126	-0.023940	-0.026334	9.841911	0.048896	0.086201	-0.034507
+9.370088	-0.004788	0.014364	9.801212	0.045565	0.086067	-0.031443
+9.371129	-0.002394	-0.035911	9.765301	0.045832	0.088466	-0.035706
+9.372129	0.035911	-0.031123	9.731785	0.047297	0.090331	-0.038904
+9.373129	0.031123	0.035911	9.786848	0.046364	0.090597	-0.036639
+9.374131	-0.014364	-0.021546	9.803606	0.045299	0.087400	-0.035306
+9.375131	-0.002394	0.002394	9.803606	0.046498	0.085534	-0.035706
+9.376131	0.019152	-0.040699	9.777271	0.044499	0.084868	-0.036772
+9.377130	0.033517	-0.021546	9.731785	0.045032	0.087933	-0.037971
+9.378134	-0.031123	0.004788	9.750937	0.047430	0.089798	-0.037971
+9.379130	-0.038305	-0.026334	9.779666	0.048763	0.088466	-0.035972
+9.380131	-0.019152	-0.028729	9.758119	0.047430	0.088599	-0.032242
+9.381131	-0.016758	0.011970	9.779666	0.047963	0.087400	-0.032508
+9.382129	0.000000	0.031123	9.837123	0.048763	0.090864	-0.035706
+9.383090	0.035911	0.033517	9.760513	0.046764	0.089665	-0.037571
+9.384128	0.002394	-0.002394	9.765301	0.046364	0.086334	-0.036639
+9.385114	-0.033517	-0.035911	9.837123	0.045698	0.085401	-0.036106
+9.386121	0.033517	-0.007182	9.885003	0.044899	0.086867	-0.035839
+9.387174	0.067033	-0.014364	9.796424	0.045032	0.088732	-0.035440
+9.388175	0.009576	-0.016758	9.791636	0.046364	0.087666	-0.034507
+9.389133	-0.007182	-0.031123	9.801212	0.047430	0.088332	-0.036505
+9.390130	-0.028729	0.007182	9.770089	0.048896	0.087400	-0.038104
+9.391116	-0.016758	0.035911	9.822758	0.048763	0.088599	-0.036106
+9.392115	0.011970	0.007182	9.794030	0.047031	0.087266	-0.036505
+9.393131	0.021546	0.057457	9.772483	0.048096	0.088199	-0.034640
+9.394095	0.004788	0.004788	9.820364	0.048629	0.088466	-0.032375
+9.395091	-0.014364	0.028729	9.784454	0.046764	0.089665	-0.038104
+9.396089	0.023940	-0.028729	9.801212	0.046897	0.089931	-0.039170
+9.397119	0.026334	-0.016758	9.837123	0.047564	0.085268	-0.032375
+9.398132	0.016758	-0.033517	9.801212	0.046498	0.082470	-0.030243
+9.399163	0.011970	-0.026334	9.863457	0.046631	0.085934	-0.033175
+9.400180	0.009576	-0.064639	9.851487	0.045698	0.088199	-0.036372
+9.401171	0.019152	0.002394	9.837123	0.044499	0.089265	-0.036372
+9.402139	-0.007182	0.007182	9.762907	0.046498	0.087933	-0.037971
+9.403130	-0.035911	-0.009576	9.791636	0.048629	0.088066	-0.037305
+9.404182	0.002394	-0.052669	9.724603	0.047164	0.087666	-0.036772
+9.405111	0.002394	0.011970	9.786848	0.045032	0.089531	-0.035573
+9.406114	0.016758	0.028729	9.868245	0.045832	0.088865	-0.034640
+9.407116	0.019152	0.059851	9.858669	0.047031	0.087400	-0.035573
+9.408111	0.016758	-0.016758	9.729391	0.047164	0.085002	-0.038237
+9.409107	-0.023940	-0.035911	9.760513	0.046897	0.086067	-0.037838
+9.410129	-0.004788	0.000000	9.784454	0.047430	0.089398	-0.036505
+9.411129	0.035911	-0.043093	9.712632	0.048629	0.090198	-0.039703
+9.412181	0.038305	-0.021546	9.736573	0.045965	0.089798	-0.037704
+9.413181	0.050275	-0.026334	9.829940	0.044100	0.087266	-0.037305
+9.414183	0.000000	-0.124490	9.791636	0.046098	0.087933	-0.035972
+9.415179	-0.057457	-0.021546	9.813182	0.049296	0.087799	-0.038637
+9.416182	0.004788	0.019152	9.837123	0.047963	0.086334	-0.038371
+9.417181	-0.031123	0.047881	9.827546	0.047430	0.088199	-0.038237
+9.418164	0.050275	0.026334	9.753331	0.047430	0.087933	-0.035839
+9.419141	0.059851	0.016758	9.801212	0.047830	0.086600	-0.034773
+9.420180	0.009576	0.002394	9.827546	0.048096	0.088332	-0.033974
+9.421182	0.011970	-0.011970	9.822758	0.047963	0.090198	-0.037305
+9.422180	-0.043093	0.028729	9.782060	0.048763	0.089931	-0.038371
+9.423176	-0.023940	0.000000	9.844305	0.048896	0.090864	-0.038637
+9.424180	0.004788	0.014364	9.822758	0.048363	0.088865	-0.036106
+9.425182	-0.002394	-0.021546	9.796424	0.047164	0.086334	-0.037305
+9.426110	0.035911	-0.035911	9.794030	0.047963	0.085668	-0.040369
+9.427098	0.023940	0.035911	9.762907	0.047963	0.085934	-0.040236
+9.428096	-0.019152	-0.007182	9.743755	0.047697	0.087266	-0.035839
+9.429091	-0.040699	0.016758	9.791636	0.047430	0.087533	-0.032508
+9.430087	-0.035911	-0.033517	9.784454	0.047697	0.087000	-0.032642
+9.431083	-0.004788	-0.011970	9.853881	0.046231	0.085801	-0.037571
+9.432095	0.043093	0.031123	9.827546	0.046631	0.083270	-0.039570
+9.433095	0.021546	0.002394	9.815576	0.045965	0.085934	-0.037838
+9.434100	0.050275	-0.047881	9.870639	0.046764	0.088998	-0.035839
+9.435101	0.011970	0.002394	9.817970	0.046897	0.090730	-0.035972
+9.436096	0.028729	-0.014364	9.748543	0.045032	0.086867	-0.035040
+9.437094	0.002394	0.021546	9.808394	0.045165	0.085934	-0.034640
+9.438101	0.019152	0.000000	9.889792	0.046498	0.086734	-0.037038
+9.439099	0.014364	0.019152	9.813182	0.046897	0.088599	-0.038637
+9.440100	0.019152	0.028729	9.794030	0.047963	0.087400	-0.036772
+9.441102	-0.004788	0.009576	9.810788	0.047297	0.088466	-0.035173
+9.442100	0.033517	0.000000	9.829940	0.048230	0.089665	-0.036372
+9.443096	0.009576	-0.023940	9.865851	0.046631	0.089398	-0.037704
+9.444099	-0.021546	-0.026334	9.827546	0.044899	0.090064	-0.035306
+9.445100	0.033517	-0.040699	9.820364	0.045565	0.087266	-0.040502
+9.446101	0.043093	-0.033517	9.827546	0.045698	0.086201	-0.041035
+9.447100	0.021546	-0.026334	9.741361	0.046098	0.087000	-0.038104
+9.448090	0.000000	-0.050275	9.829940	0.046098	0.089265	-0.035440
+9.449097	0.033517	-0.009576	9.820364	0.045165	0.088332	-0.033441
+9.450099	0.064639	-0.007182	9.803606	0.044766	0.086734	-0.035440
+9.451100	0.088580	-0.031123	9.813182	0.045565	0.085534	-0.038770
+9.452090	0.062245	-0.059851	9.726997	0.045432	0.086734	-0.039037
+9.453095	0.011970	-0.016758	9.676722	0.044366	0.088066	-0.038104
+9.454096	0.019152	-0.055063	9.837123	0.045698	0.086734	-0.037971
+9.455094	0.050275	-0.067033	9.822758	0.048496	0.085668	-0.034107
+9.456094	0.043093	-0.071821	9.772483	0.045698	0.086201	-0.031975
+9.457091	0.043093	-0.016758	9.875427	0.044632	0.087133	-0.034640
+9.458111	0.043093	0.062245	9.844305	0.045165	0.087799	-0.038770
+9.459094	0.059851	0.035911	9.827546	0.047031	0.085668	-0.038504
+9.460088	0.023940	-0.016758	9.851487	0.047564	0.085401	-0.035839
+9.461095	0.035911	-0.043093	9.820364	0.048363	0.087933	-0.033175
+9.462094	-0.004788	0.059851	9.832334	0.046764	0.087933	-0.034773
+9.463096	-0.004788	-0.007182	9.748543	0.045965	0.087666	-0.036505
+9.464095	-0.019152	-0.047881	9.719814	0.047830	0.086600	-0.040103
+9.465096	-0.002394	-0.023940	9.832334	0.047697	0.086600	-0.037571
+9.466095	0.050275	-0.019152	9.789242	0.049162	0.087533	-0.033574
+9.467089	0.050275	-0.016758	9.841911	0.049162	0.088466	-0.036239
+9.468096	-0.014364	0.009576	9.820364	0.046764	0.089132	-0.038770
+9.469092	-0.002394	0.014364	9.815576	0.045299	0.088865	-0.035573
+9.470123	-0.035911	-0.038305	9.820364	0.046897	0.087533	-0.033974
+9.471112	-0.028729	-0.016758	9.794030	0.046498	0.089665	-0.035839
+9.472110	-0.031123	-0.019152	9.786848	0.045698	0.091130	-0.036239
+9.473114	-0.019152	-0.021546	9.803606	0.046631	0.090198	-0.036372
+9.474113	0.035911	-0.047881	9.820364	0.049695	0.088066	-0.034240
+9.475136	0.057457	-0.040699	9.731785	0.049695	0.086067	-0.035706
+9.476119	0.016758	-0.011970	9.899368	0.047564	0.085135	-0.036639
+9.477174	-0.004788	0.011970	9.827546	0.047164	0.088066	-0.036505
+9.478138	0.026334	0.000000	9.810788	0.046631	0.087133	-0.040236
+9.479139	0.011970	-0.026334	9.853881	0.047031	0.086201	-0.036905
+9.480130	-0.007182	-0.007182	9.803606	0.047564	0.089398	-0.033841
+9.481128	0.033517	0.014364	9.774877	0.047697	0.089265	-0.034374
+9.482126	0.047881	0.035911	9.729391	0.047830	0.088732	-0.037172
+9.483180	0.004788	0.031123	9.734179	0.046231	0.088332	-0.035839
+9.484179	0.009576	0.055063	9.813182	0.045698	0.089265	-0.036106
+9.485122	-0.083792	-0.011970	9.858669	0.045965	0.087533	-0.033574
+9.486179	-0.035911	-0.057457	9.750937	0.047830	0.087133	-0.035573
+9.487165	-0.033517	-0.033517	9.729391	0.050095	0.088998	-0.037971
+9.488118	0.000000	0.011970	9.767695	0.050761	0.088732	-0.038371
+9.489111	-0.007182	-0.011970	9.832334	0.049029	0.089531	-0.037305
+9.490178	0.023940	-0.035911	9.789242	0.046764	0.086201	-0.039303
+9.491125	-0.043093	-0.021546	9.829940	0.045832	0.084602	-0.035706
+9.492140	-0.023940	-0.055063	9.865851	0.045698	0.084602	-0.033574
+9.493131	-0.031123	-0.019152	9.858669	0.046631	0.085401	-0.034107
+9.494180	-0.038305	-0.052669	9.806000	0.046764	0.088199	-0.036239
+9.495177	0.033517	-0.011970	9.791636	0.046231	0.088599	-0.035040
+9.496176	0.016758	0.062245	9.806000	0.047430	0.088199	-0.035706
+9.497177	-0.028729	-0.011970	9.813182	0.047697	0.087799	-0.036505
+9.498127	-0.062245	-0.064639	9.815576	0.047564	0.086734	-0.035706
+9.499136	0.009576	-0.062245	9.774877	0.049162	0.086734	-0.035706
+9.500168	0.004788	-0.031123	9.755725	0.051161	0.088865	-0.033574
+9.501176	0.028729	-0.055063	9.774877	0.050761	0.088998	-0.033841
+9.502105	0.021546	-0.007182	9.808394	0.047031	0.087133	-0.038637
+9.503109	0.050275	-0.004788	9.837123	0.045299	0.086334	-0.037438
+9.504179	0.031123	0.014364	9.796424	0.044632	0.087000	-0.035040
+9.505183	0.052669	0.062245	9.808394	0.046631	0.087400	-0.035040
+9.506182	0.016758	0.016758	9.777271	0.046897	0.086467	-0.033841
+9.507181	-0.014364	-0.014364	9.765301	0.047564	0.088332	-0.035173
+9.508144	-0.014364	0.057457	9.734179	0.046897	0.088599	-0.034240
+9.509140	0.007182	0.047881	9.817970	0.047031	0.088199	-0.036905
+9.510135	0.028729	-0.004788	9.846699	0.048363	0.089265	-0.040236
+9.511120	0.043093	-0.047881	9.810788	0.047564	0.092063	-0.037838
+9.512180	-0.028729	0.035911	9.753331	0.047164	0.093795	-0.034907
+9.513179	-0.040699	0.057457	9.724603	0.047297	0.088732	-0.032908
+9.514183	0.043093	-0.031123	9.784454	0.047297	0.083936	-0.029844
+9.515113	-0.002394	-0.038305	9.813182	0.047297	0.084335	-0.031709
+9.516119	0.009576	-0.045487	9.813182	0.047564	0.087400	-0.035440
+9.517118	0.040699	0.031123	9.827546	0.047031	0.087400	-0.035573
+9.518137	0.050275	0.016758	9.841911	0.048096	0.087666	-0.035706
+9.519177	0.014364	-0.031123	9.858669	0.046631	0.088466	-0.037038
+9.520161	-0.043093	-0.043093	9.803606	0.044766	0.089132	-0.036372
+9.521178	-0.023940	0.000000	9.844305	0.046231	0.088466	-0.037305
+9.522128	0.011970	-0.014364	9.880215	0.049562	0.085268	-0.037438
+9.523177	0.002394	-0.014364	9.894580	0.049029	0.083136	-0.033708
+9.524180	0.026334	-0.035911	9.820364	0.045832	0.084335	-0.033974
+9.525177	-0.007182	-0.047881	9.789242	0.044100	0.086734	-0.036772
+9.526172	0.000000	-0.033517	9.875427	0.045565	0.085534	-0.038371
+9.527178	0.014364	0.014364	9.896974	0.049828	0.088466	-0.037704
+9.528144	0.011970	0.000000	9.911338	0.049828	0.088332	-0.037305
+9.529183	-0.002394	-0.021546	9.839517	0.047697	0.085268	-0.036106
+9.530179	0.007182	-0.019152	9.875427	0.045565	0.086067	-0.036639
+9.531158	-0.004788	-0.016758	9.817970	0.048763	0.088332	-0.037038
+9.532116	0.002394	0.019152	9.796424	0.049562	0.088332	-0.037704
+9.533173	0.009576	-0.019152	9.803606	0.048629	0.086334	-0.034374
+9.534153	0.050275	-0.028729	9.829940	0.046231	0.088599	-0.036772
+9.535110	-0.033517	0.007182	9.820364	0.047830	0.090331	-0.034240
+9.536171	-0.002394	0.035911	9.806000	0.047697	0.088466	-0.033841
+9.537129	0.019152	0.031123	9.741361	0.048629	0.087533	-0.034507
+9.538183	0.021546	-0.040699	9.743755	0.048496	0.085401	-0.034507
+9.539135	-0.014364	-0.002394	9.877821	0.047297	0.084469	-0.033441
+9.540176	-0.002394	-0.004788	9.827546	0.046897	0.086600	-0.035573
+9.541181	-0.023940	-0.040699	9.803606	0.047963	0.088732	-0.036772
+9.542139	-0.014364	-0.055063	9.806000	0.047963	0.085801	-0.036505
+9.543142	0.021546	-0.002394	9.791636	0.045032	0.085534	-0.036372
+9.544184	0.023940	0.031123	9.820364	0.046098	0.087266	-0.036772
+9.545179	-0.023940	0.007182	9.712632	0.048096	0.086467	-0.035839
+9.546178	0.004788	-0.002394	9.717420	0.048763	0.086600	-0.035173
+9.547178	0.009576	-0.033517	9.837123	0.048363	0.087400	-0.036239
+9.548171	0.021546	-0.083792	9.892186	0.046098	0.087533	-0.036505
+9.549179	0.023940	-0.038305	9.851487	0.043567	0.087266	-0.034640
+9.550188	0.055063	-0.002394	9.760513	0.044899	0.087533	-0.032242
+9.551140	0.045487	0.000000	9.765301	0.045965	0.088066	-0.033041
+9.552184	-0.016758	0.023940	9.841911	0.045698	0.087400	-0.038237
+9.553164	-0.021546	0.021546	9.810788	0.047830	0.088466	-0.037971
+9.554174	0.014364	0.040699	9.741361	0.045965	0.087799	-0.037971
+9.555178	-0.011970	0.021546	9.827546	0.045565	0.085534	-0.035839
+9.556180	0.059851	0.011970	9.808394	0.045965	0.087933	-0.036905
+9.557177	0.000000	0.016758	9.858669	0.045965	0.089531	-0.033708
+9.558180	-0.014364	0.016758	9.863457	0.045565	0.087799	-0.032375
+9.559150	0.002394	-0.067033	9.837123	0.045565	0.087666	-0.031176
+9.560121	-0.026334	-0.023940	9.827546	0.044899	0.087799	-0.033308
+9.561178	-0.028729	-0.031123	9.798818	0.046764	0.087533	-0.037038
+9.562175	0.016758	0.040699	9.784454	0.047564	0.087266	-0.037172
+9.563169	-0.002394	0.028729	9.803606	0.047564	0.084602	-0.034640
+9.564194	-0.047881	0.016758	9.880215	0.046098	0.087266	-0.033841
+9.565176	0.009576	-0.019152	9.794030	0.046231	0.088998	-0.035839
+9.566181	0.016758	-0.028729	9.762907	0.047297	0.089531	-0.037838
+9.567178	0.062245	-0.019152	9.851487	0.047697	0.087799	-0.034907
+9.568172	0.026334	-0.062245	9.796424	0.046631	0.088466	-0.031975
+9.569177	0.038305	-0.079003	9.825152	0.047297	0.088599	-0.032775
+9.570173	0.023940	-0.047881	9.889792	0.049296	0.087133	-0.037438
+9.571177	0.000000	-0.043093	9.779666	0.049162	0.086334	-0.038637
+9.572175	0.021546	0.035911	9.846699	0.046764	0.088199	-0.037438
+9.573168	-0.021546	0.021546	9.825152	0.045165	0.090331	-0.036639
+9.574174	0.014364	-0.038305	9.767695	0.045565	0.089132	-0.036639
+9.575178	-0.004788	-0.045487	9.746149	0.046498	0.086467	-0.035573
+9.576155	0.019152	-0.002394	9.803606	0.048096	0.085668	-0.037571
+9.577176	0.031123	0.033517	9.813182	0.047697	0.086467	-0.036372
+9.578180	-0.033517	-0.057457	9.784454	0.046231	0.087000	-0.037172
+9.579175	-0.035911	-0.090974	9.760513	0.045965	0.086734	-0.035972
+9.580175	-0.023940	-0.052669	9.808394	0.046498	0.090864	-0.037571
+9.581177	0.019152	0.009576	9.887397	0.048363	0.090064	-0.036772
+9.582175	-0.021546	-0.043093	9.791636	0.048096	0.084735	-0.033441
+9.583159	-0.023940	-0.011970	9.741361	0.047164	0.083270	-0.034907
+9.584161	-0.047881	0.021546	9.765301	0.048230	0.087133	-0.038237
+9.585176	0.016758	0.031123	9.762907	0.048763	0.090464	-0.035306
+9.586132	0.000000	-0.009576	9.868245	0.046897	0.088066	-0.036505
+9.587170	-0.004788	-0.026334	9.832334	0.045698	0.086201	-0.036639
+9.588176	-0.035911	0.035911	9.794030	0.047697	0.087799	-0.036905
+9.589175	-0.014364	-0.062245	9.748543	0.047297	0.087799	-0.037971
+9.590180	0.004788	-0.064639	9.741361	0.046764	0.087400	-0.037438
+9.591175	0.009576	-0.021546	9.875427	0.048629	0.087266	-0.040236
+9.592161	0.031123	-0.047881	9.865851	0.047564	0.089398	-0.038637
+9.593154	-0.021546	-0.031123	9.837123	0.047963	0.088599	-0.036905
+9.594138	-0.011970	0.026334	9.837123	0.047963	0.086334	-0.035306
+9.595179	0.047881	0.059851	9.803606	0.048096	0.087000	-0.035839
+9.596178	0.047881	-0.031123	9.801212	0.048896	0.087799	-0.036106
+9.597176	-0.011970	-0.088580	9.777271	0.049429	0.087533	-0.035839
+9.598120	-0.019152	-0.055063	9.770089	0.048763	0.084202	-0.036372
+9.599128	0.011970	-0.014364	9.779666	0.049029	0.087799	-0.035573
+9.600126	0.004788	0.009576	9.810788	0.048896	0.090730	-0.036372
+9.601130	-0.007182	-0.009576	9.822758	0.046897	0.091130	-0.037438
+9.602127	0.026334	-0.035911	9.815576	0.046098	0.086734	-0.034773
+9.603126	-0.035911	-0.057457	9.738967	0.045432	0.087133	-0.034374
+9.604127	-0.079003	-0.016758	9.762907	0.046631	0.089132	-0.035173
+9.605131	-0.035911	-0.016758	9.829940	0.044499	0.088732	-0.036106
+9.606132	-0.004788	-0.011970	9.889792	0.046364	0.087533	-0.036239
+9.607127	0.016758	-0.011970	9.911338	0.045565	0.086600	-0.036372
+9.608127	0.002394	-0.033517	9.849093	0.044366	0.084735	-0.033974
+9.609114	0.023940	-0.002394	9.758119	0.043433	0.084868	-0.036905
+9.610114	0.000000	-0.035911	9.748543	0.045432	0.085401	-0.038104
+9.611095	0.007182	0.007182	9.748543	0.049296	0.084069	-0.036239
+9.612120	-0.014364	-0.033517	9.767695	0.048629	0.084202	-0.036372
+9.613101	0.007182	0.014364	9.868245	0.047297	0.087799	-0.035706
+9.614174	0.007182	0.002394	9.952037	0.048230	0.087533	-0.037172
+9.615176	0.002394	-0.004788	9.901762	0.044366	0.088732	-0.036505
+9.616176	-0.016758	0.004788	9.789242	0.043034	0.088199	-0.035972
+9.617162	-0.028729	0.011970	9.794030	0.046764	0.087000	-0.034640
+9.618103	0.002394	0.011970	9.726997	0.048230	0.087133	-0.037172
+9.619090	0.014364	-0.081397	9.789242	0.048096	0.083936	-0.039703
+9.620109	0.057457	-0.035911	9.846699	0.045299	0.083536	-0.036905
+9.621099	0.045487	-0.007182	9.794030	0.043300	0.085668	-0.033974
+9.622099	0.004788	-0.007182	9.798818	0.045565	0.087133	-0.035972
+9.623173	0.002394	-0.021546	9.760513	0.046231	0.089265	-0.036905
+9.624178	0.014364	-0.028729	9.803606	0.044499	0.089931	-0.039570
+9.625177	0.014364	0.000000	9.803606	0.044366	0.087666	-0.038637
+9.626131	-0.014364	-0.016758	9.786848	0.045965	0.087533	-0.035173
+9.627176	0.067033	-0.047881	9.758119	0.046498	0.089931	-0.032908
+9.628183	-0.009576	0.019152	9.758119	0.047031	0.089265	-0.035173
+9.629131	-0.028729	0.014364	9.825152	0.047297	0.089665	-0.037704
+9.630201	-0.033517	0.016758	9.875427	0.048230	0.089398	-0.037704
+9.631177	0.023940	0.033517	9.810788	0.047830	0.088732	-0.037704
+9.632179	0.019152	0.035911	9.760513	0.049162	0.089531	-0.033708
+9.633177	-0.002394	0.007182	9.741361	0.049162	0.087000	-0.034374
+9.634177	-0.014364	-0.043093	9.786848	0.046764	0.085268	-0.038504
+9.635114	0.007182	-0.004788	9.791636	0.047564	0.086201	-0.037838
+9.636119	-0.002394	-0.023940	9.822758	0.046498	0.088199	-0.036239
+9.637088	-0.014364	-0.047881	9.846699	0.045299	0.089132	-0.035839
+9.638174	0.019152	0.004788	9.839517	0.046764	0.087933	-0.037038
+9.639178	0.007182	0.009576	9.877821	0.047430	0.087799	-0.033175
+9.640149	0.038305	-0.040699	9.784454	0.046897	0.087400	-0.031842
+9.641179	0.002394	-0.047881	9.815576	0.048896	0.088865	-0.032242
+9.642183	0.031123	-0.093368	9.679116	0.050228	0.088332	-0.034907
+9.643175	0.052669	-0.031123	9.815576	0.050361	0.091397	-0.036639
+9.644174	-0.016758	-0.011970	9.822758	0.048496	0.092329	-0.037438
+9.645175	0.050275	-0.009576	9.736573	0.047164	0.090331	-0.040236
+9.646177	0.026334	-0.038305	9.782060	0.047697	0.086334	-0.036372
+9.647175	0.019152	0.023940	9.822758	0.046631	0.086334	-0.037704
+9.648175	-0.021546	0.035911	9.825152	0.045832	0.086467	-0.037704
+9.649176	-0.035911	-0.023940	9.817970	0.045965	0.088599	-0.036372
+9.650158	0.000000	-0.002394	9.786848	0.047164	0.088066	-0.037038
+9.651151	0.062245	0.014364	9.782060	0.047430	0.087266	-0.035173
+9.652132	0.033517	-0.038305	9.877821	0.047830	0.086734	-0.036772
+9.653180	0.045487	-0.002394	9.803606	0.046897	0.088466	-0.039703
+9.654178	-0.016758	0.031123	9.810788	0.045165	0.088066	-0.038104
+9.655175	0.009576	0.016758	9.789242	0.046631	0.087533	-0.038104
+9.656161	-0.007182	0.043093	9.760513	0.048896	0.088332	-0.036905
+9.657182	0.004788	0.000000	9.765301	0.047564	0.087799	-0.035839
+9.658177	0.086186	-0.016758	9.791636	0.045832	0.088066	-0.037438
+9.659138	0.038305	0.000000	9.794030	0.046764	0.087799	-0.036505
+9.660126	0.016758	-0.021546	9.779666	0.047963	0.086734	-0.036239
+9.661162	0.038305	0.007182	9.717420	0.047164	0.086600	-0.039303
+9.662118	-0.014364	0.014364	9.748543	0.047430	0.089265	-0.040902
+9.663175	0.004788	0.040699	9.853881	0.047297	0.087400	-0.034374
+9.664129	0.007182	0.004788	9.841911	0.045965	0.085268	-0.032908
+9.665132	0.045487	-0.007182	9.825152	0.047031	0.084069	-0.036772
+9.666137	0.052669	-0.033517	9.841911	0.048629	0.087266	-0.036372
+9.667174	0.043093	-0.011970	9.889792	0.047963	0.088865	-0.037438
+9.668118	0.055063	0.016758	9.717420	0.047963	0.088599	-0.037172
+9.669176	0.040699	0.040699	9.746149	0.047963	0.089132	-0.040769
+9.670179	0.062245	-0.011970	9.791636	0.046498	0.088732	-0.041302
+9.671168	0.043093	-0.009576	9.851487	0.045565	0.088066	-0.038104
+9.672142	0.076609	-0.023940	9.873033	0.043567	0.087666	-0.033841
+9.673204	0.004788	0.009576	9.906550	0.044499	0.089265	-0.035173
+9.674178	-0.059851	-0.009576	9.882609	0.044899	0.088332	-0.034907
+9.675178	-0.016758	-0.016758	9.808394	0.046897	0.087799	-0.037571
+9.676175	0.002394	0.016758	9.803606	0.048763	0.088066	-0.036905
+9.677177	-0.019152	0.014364	9.837123	0.047297	0.088998	-0.035440
+9.678178	-0.014364	0.023940	9.827546	0.044766	0.089931	-0.033574
+9.679172	0.011970	-0.019152	9.806000	0.046098	0.087533	-0.033175
+9.680130	0.035911	0.023940	9.801212	0.046098	0.088199	-0.035706
+9.681176	-0.016758	-0.016758	9.806000	0.045432	0.089265	-0.035972
+9.682140	-0.035911	-0.059851	9.765301	0.048363	0.088732	-0.035040
+9.683170	-0.052669	-0.076609	9.806000	0.047564	0.088332	-0.036905
+9.684178	-0.007182	-0.040699	9.868245	0.045299	0.088865	-0.037172
+9.685169	0.028729	-0.009576	9.822758	0.043700	0.088466	-0.036905
+9.686085	0.067033	-0.059851	9.889792	0.043300	0.085801	-0.039037
+9.687174	0.055063	-0.009576	9.841911	0.045432	0.085801	-0.037438
+9.688173	0.035911	0.007182	9.746149	0.047164	0.087000	-0.037038
+9.689102	0.040699	-0.016758	9.808394	0.046498	0.088599	-0.036905
+9.690099	0.033517	-0.009576	9.796424	0.045698	0.086334	-0.036372
+9.691172	0.004788	0.035911	9.827546	0.047297	0.084735	-0.038770
+9.692175	-0.014364	-0.014364	9.726997	0.047963	0.087000	-0.039436
+9.693177	0.002394	-0.021546	9.712632	0.049296	0.085534	-0.040636
+9.694131	0.038305	0.007182	9.707844	0.045832	0.084868	-0.036372
+9.695172	0.035911	-0.011970	9.755725	0.047164	0.086467	-0.035972
+9.696175	0.021546	-0.009576	9.858669	0.048363	0.088865	-0.037571
+9.697178	0.002394	0.086186	9.887397	0.049162	0.087400	-0.035972
+9.698138	0.004788	0.021546	9.844305	0.048763	0.086600	-0.038237
+9.699137	0.050275	-0.033517	9.815576	0.045165	0.084868	-0.039303
+9.700175	0.040699	-0.069427	9.832334	0.041835	0.085002	-0.038237
+9.701175	0.043093	-0.021546	9.789242	0.042900	0.088998	-0.037172
+9.702180	0.057457	-0.002394	9.794030	0.044366	0.089265	-0.034640
+9.703176	0.019152	-0.002394	9.765301	0.045698	0.088865	-0.036639
+9.704165	-0.011970	0.014364	9.813182	0.045032	0.088732	-0.037971
+9.705168	-0.007182	0.007182	9.849093	0.046364	0.089132	-0.033175
+9.706178	-0.007182	0.064639	9.868245	0.049029	0.086467	-0.031842
+9.707174	-0.035911	0.000000	9.882609	0.049562	0.087133	-0.033841
+9.708172	0.047881	0.069427	9.798818	0.048096	0.090597	-0.038904
+9.709128	0.033517	0.028729	9.722208	0.044632	0.092196	-0.036905
+9.710119	-0.031123	-0.009576	9.863457	0.045299	0.089798	-0.037038
+9.711174	-0.002394	-0.074215	9.841911	0.042101	0.087400	-0.037438
+9.712130	0.019152	0.000000	9.801212	0.042900	0.087666	-0.036905
+9.713112	0.055063	-0.016758	9.827546	0.046498	0.089265	-0.037838
+9.714100	0.021546	-0.028729	9.882609	0.046764	0.090198	-0.034640
+9.715097	0.055063	-0.007182	9.861063	0.047031	0.087666	-0.032242
+9.716111	0.035911	0.023940	9.837123	0.045965	0.088066	-0.032109
+9.717100	0.019152	-0.007182	9.813182	0.044366	0.088066	-0.032109
+9.718174	0.016758	-0.011970	9.765301	0.045832	0.090331	-0.034640
+9.719151	-0.033517	-0.038305	9.798818	0.046231	0.089798	-0.034640
+9.720159	-0.016758	0.000000	9.858669	0.045565	0.089132	-0.033574
+9.721162	0.002394	0.040699	9.817970	0.047430	0.090997	-0.035173
+9.722104	-0.045487	0.007182	9.940066	0.047430	0.089665	-0.035972
+9.723101	-0.014364	0.047881	9.880215	0.046231	0.085135	-0.037172
+9.724101	-0.004788	0.014364	9.844305	0.049828	0.086734	-0.035440
+9.725097	0.019152	-0.009576	9.772483	0.049029	0.090864	-0.032109
+9.726134	-0.016758	-0.064639	9.734179	0.048363	0.089931	-0.031842
+9.727118	-0.045487	0.007182	9.801212	0.046897	0.088466	-0.035972
+9.728132	0.002394	-0.011970	9.798818	0.048363	0.088332	-0.036772
+9.729134	-0.026334	-0.009576	9.741361	0.047564	0.088998	-0.037038
+9.730101	0.007182	0.000000	9.746149	0.047963	0.089398	-0.037438
+9.731149	0.016758	-0.016758	9.760513	0.046498	0.087266	-0.035839
+9.732133	0.014364	-0.023940	9.738967	0.046897	0.085135	-0.034240
+9.733128	-0.023940	0.021546	9.746149	0.046231	0.086467	-0.036639
+9.734110	0.000000	0.000000	9.729391	0.046364	0.088199	-0.041168
+9.735113	0.031123	-0.004788	9.767695	0.045299	0.088998	-0.041435
+9.736101	0.023940	-0.011970	9.844305	0.046498	0.087933	-0.036505
+9.737134	-0.011970	-0.009576	9.760513	0.047430	0.086734	-0.035440
+9.738142	-0.074215	0.057457	9.736573	0.046631	0.087266	-0.036239
+9.739105	-0.047881	-0.002394	9.772483	0.047564	0.087533	-0.036505
+9.740177	0.064639	-0.014364	9.741361	0.048763	0.088332	-0.036505
+9.741173	0.007182	-0.023940	9.782060	0.048363	0.088066	-0.035173
+9.742176	0.055063	-0.064639	9.846699	0.046897	0.087533	-0.035706
+9.743180	0.057457	-0.047881	9.815576	0.046897	0.088199	-0.036639
+9.744178	-0.004788	-0.035911	9.908944	0.047031	0.089265	-0.036106
+9.745180	-0.035911	0.009576	9.839517	0.045965	0.088066	-0.037971
+9.746180	-0.026334	0.071821	9.755725	0.045565	0.086467	-0.037838
+9.747177	-0.021546	0.026334	9.875427	0.045432	0.087666	-0.037438
+9.748123	-0.007182	0.016758	9.837123	0.047031	0.087799	-0.039037
+9.749179	0.004788	-0.023940	9.825152	0.050495	0.088732	-0.037438
+9.750172	-0.011970	-0.038305	9.748543	0.049828	0.087666	-0.036905
+9.751126	-0.007182	-0.019152	9.784454	0.047564	0.087799	-0.039303
+9.752149	-0.047881	-0.071821	9.784454	0.049029	0.086867	-0.039703
+9.753178	-0.019152	-0.040699	9.846699	0.046631	0.087000	-0.033574
+9.754090	0.055063	0.016758	9.767695	0.045432	0.087133	-0.033974
+9.755084	0.028729	0.031123	9.760513	0.044632	0.089665	-0.037704
+9.756131	-0.011970	0.011970	9.794030	0.043700	0.090331	-0.038770
+9.757159	-0.007182	-0.004788	9.810788	0.046631	0.086334	-0.037438
+9.758187	0.033517	-0.019152	9.834729	0.048363	0.087666	-0.037172
+9.759131	0.023940	-0.052669	9.820364	0.046498	0.091263	-0.036239
+9.760173	-0.023940	-0.045487	9.774877	0.044632	0.090198	-0.035972
+9.761174	-0.009576	-0.081397	9.724603	0.046897	0.086734	-0.039969
+9.762157	0.002394	-0.055063	9.798818	0.049429	0.086334	-0.035573
+9.763156	0.009576	0.002394	9.834729	0.049296	0.089931	-0.032908
+9.764178	0.045487	0.011970	9.858669	0.044766	0.092196	-0.032375
+9.765180	0.000000	-0.045487	9.861063	0.045965	0.090198	-0.034907
+9.766179	-0.043093	-0.031123	9.853881	0.047564	0.088466	-0.037971
+9.767118	-0.014364	-0.004788	9.899368	0.047164	0.087266	-0.038637
+9.768130	0.033517	0.011970	9.784454	0.048896	0.086867	-0.038371
+9.769153	0.031123	0.011970	9.796424	0.046897	0.087666	-0.036239
+9.770115	0.007182	-0.004788	9.827546	0.046364	0.086201	-0.033841
+9.771113	0.011970	-0.055063	9.760513	0.045832	0.086467	-0.034507
+9.772119	-0.019152	-0.059851	9.832334	0.046631	0.088998	-0.035440
+9.773164	-0.007182	-0.009576	9.772483	0.047164	0.088998	-0.036639
+9.774194	-0.031123	-0.040699	9.803606	0.046098	0.087799	-0.038371
+9.775178	-0.057457	-0.023940	9.825152	0.044233	0.087666	-0.037438
+9.776179	0.028729	-0.052669	9.815576	0.045432	0.088599	-0.034240
+9.777139	0.079003	-0.064639	9.815576	0.046631	0.086867	-0.035972
+9.778121	0.047881	-0.050275	9.796424	0.047830	0.087933	-0.037571
+9.779176	-0.002394	-0.047881	9.808394	0.044899	0.088998	-0.034773
+9.780178	-0.038305	-0.038305	9.794030	0.044499	0.088599	-0.036772
+9.781179	0.000000	-0.033517	9.853881	0.046098	0.087666	-0.036772
+9.782173	0.002394	-0.043093	9.777271	0.047830	0.086867	-0.036372
+9.783169	0.045487	0.002394	9.762907	0.045165	0.085934	-0.038637
+9.784116	-0.007182	0.014364	9.755725	0.045965	0.086334	-0.037438
+9.785122	0.031123	-0.026334	9.798818	0.047164	0.086201	-0.036505
+9.786100	0.007182	-0.045487	9.837123	0.045965	0.090331	-0.035839
+9.787172	-0.023940	-0.033517	9.825152	0.047164	0.089931	-0.034374
+9.788179	0.021546	-0.016758	9.791636	0.045032	0.088199	-0.038371
+9.789179	0.033517	-0.004788	9.794030	0.045965	0.088332	-0.039303
+9.790180	-0.011970	0.023940	9.815576	0.043700	0.090331	-0.035573
+9.791178	-0.016758	0.019152	9.806000	0.045299	0.090864	-0.033441
+9.792106	0.026334	-0.026334	9.765301	0.046098	0.089265	-0.038637
+9.793180	-0.031123	0.000000	9.817970	0.046364	0.087533	-0.039836
+9.794178	-0.026334	0.031123	9.808394	0.048763	0.084602	-0.038237
+9.795184	-0.011970	0.002394	9.741361	0.048096	0.086467	-0.034374
+9.796145	0.055063	-0.023940	9.777271	0.045965	0.088466	-0.035306
+9.797168	-0.009576	-0.050275	9.784454	0.046631	0.087799	-0.036905
+9.798118	0.019152	-0.011970	9.767695	0.046631	0.085002	-0.037838
+9.799150	-0.002394	-0.011970	9.755725	0.044632	0.084469	-0.035573
+9.800133	0.007182	0.014364	9.813182	0.044899	0.088066	-0.035173
+9.801125	-0.002394	0.040699	9.765301	0.046631	0.087400	-0.035440
+9.802179	-0.050275	-0.007182	9.841911	0.045432	0.084735	-0.037305
+9.803179	-0.043093	-0.016758	9.844305	0.043700	0.085534	-0.035706
+9.804172	0.033517	0.011970	9.726997	0.047430	0.086734	-0.037438
+9.805179	0.028729	-0.016758	9.762907	0.047430	0.085135	-0.038904
+9.806179	-0.019152	0.011970	9.796424	0.048230	0.085135	-0.034907
+9.807176	0.057457	0.014364	9.820364	0.046897	0.086067	-0.032775
+9.808160	0.076609	-0.007182	9.868245	0.046364	0.086867	-0.034107
+9.809139	0.052669	0.004788	9.825152	0.045965	0.087666	-0.035173
+9.810131	-0.016758	-0.040699	9.875427	0.046364	0.089665	-0.035040
+9.811118	-0.031123	-0.011970	9.846699	0.046631	0.089798	-0.037571
+9.812177	0.007182	0.028729	9.863457	0.046897	0.088466	-0.037038
+9.813174	-0.016758	-0.019152	9.784454	0.046631	0.090997	-0.033841
+9.814180	0.007182	-0.021546	9.822758	0.046764	0.088199	-0.034907
+9.815178	0.035911	0.021546	9.815576	0.046364	0.087400	-0.037038
+9.816179	0.026334	-0.023940	9.832334	0.047164	0.086067	-0.037704
+9.817180	0.031123	-0.055063	9.853881	0.046231	0.088466	-0.036905
+9.818184	0.011970	-0.047881	9.762907	0.047164	0.088599	-0.035972
+9.819149	0.035911	-0.023940	9.715026	0.043833	0.087533	-0.039436
+9.820177	0.002394	0.019152	9.832334	0.043034	0.088732	-0.043700
+9.821173	-0.040699	-0.002394	9.837123	0.045832	0.087799	-0.041035
+9.822179	-0.023940	-0.002394	9.798818	0.048496	0.088066	-0.039570
+9.823179	0.009576	-0.095762	9.796424	0.048629	0.087133	-0.035306
+9.824178	0.000000	-0.033517	9.786848	0.046498	0.087133	-0.035440
+9.825179	0.016758	0.000000	9.868245	0.046231	0.087133	-0.037305
+9.826175	0.086186	0.000000	9.786848	0.047297	0.086334	-0.035972
+9.827174	0.064639	0.033517	9.808394	0.045432	0.090198	-0.036372
+9.828186	0.021546	0.016758	9.817970	0.046098	0.090730	-0.034374
+9.829137	0.067033	-0.011970	9.829940	0.047564	0.085801	-0.036372
+9.830179	0.062245	0.000000	9.779666	0.045165	0.086201	-0.039303
+9.831175	-0.016758	0.052669	9.734179	0.047031	0.089265	-0.036505
+9.832178	-0.028729	-0.002394	9.746149	0.048629	0.087933	-0.035173
+9.833178	0.016758	-0.055063	9.770089	0.048763	0.089265	-0.034907
+9.834164	0.004788	-0.023940	9.770089	0.046098	0.088732	-0.034640
+9.835174	0.074215	-0.007182	9.784454	0.045565	0.089265	-0.035440
+9.836117	0.045487	0.007182	9.834729	0.046897	0.091530	-0.035839
+9.837171	0.055063	0.007182	9.698268	0.049296	0.091930	-0.033308
+9.838181	0.011970	-0.016758	9.786848	0.047297	0.090198	-0.032109
+9.839131	0.043093	-0.035911	9.841911	0.047430	0.088732	-0.033841
+9.840159	0.014364	0.009576	9.873033	0.046364	0.086734	-0.033708
+9.841178	-0.047881	-0.028729	9.858669	0.044632	0.089265	-0.035972
+9.842179	-0.004788	-0.052669	9.827546	0.045299	0.088998	-0.037172
+9.843178	0.014364	-0.047881	9.806000	0.048230	0.087666	-0.035173
+9.844174	0.019152	-0.040699	9.782060	0.046897	0.086734	-0.036106
+9.845179	0.014364	-0.019152	9.794030	0.045165	0.085934	-0.035839
+9.846182	0.043093	-0.064639	9.741361	0.044100	0.085934	-0.034640
+9.847172	0.023940	-0.009576	9.765301	0.047430	0.089398	-0.036772
+9.848169	0.009576	0.028729	9.784454	0.048496	0.091796	-0.036639
+9.849162	-0.002394	-0.004788	9.832334	0.045698	0.090730	-0.035972
+9.850166	-0.007182	-0.026334	9.873033	0.047830	0.087400	-0.041302
+9.851158	0.004788	-0.007182	9.885003	0.047297	0.086067	-0.040103
+9.852179	0.038305	0.002394	9.882609	0.047164	0.086334	-0.035706
+9.853179	-0.031123	0.043093	9.791636	0.046231	0.086201	-0.035306
+9.854180	-0.031123	0.014364	9.782060	0.045299	0.089531	-0.036505
+9.855179	-0.019152	-0.023940	9.779666	0.046364	0.087000	-0.035573
+9.856178	0.002394	-0.055063	9.815576	0.047297	0.086334	-0.036239
+9.857176	0.040699	0.023940	9.755725	0.046631	0.088332	-0.035040
+9.858155	0.021546	0.004788	9.889792	0.047430	0.091663	-0.036505
+9.859131	0.009576	0.021546	9.810788	0.047031	0.091130	-0.036106
+9.860130	0.019152	-0.035911	9.700662	0.047430	0.088066	-0.034240
+9.861133	0.033517	-0.009576	9.760513	0.048096	0.086334	-0.033175
+9.862179	0.031123	0.002394	9.794030	0.047164	0.088066	-0.033841
+9.863178	0.052669	-0.019152	9.765301	0.047697	0.088865	-0.033041
+9.864177	-0.016758	-0.014364	9.789242	0.046897	0.086867	-0.036639
+9.865179	0.009576	-0.019152	9.762907	0.047963	0.085268	-0.039436
+9.866150	0.019152	-0.064639	9.798818	0.045965	0.086867	-0.037971
+9.867071	0.043093	0.007182	9.806000	0.047963	0.088466	-0.035839
+9.868172	0.023940	0.071821	9.815576	0.047830	0.086867	-0.035306
+9.869171	0.011970	0.021546	9.815576	0.048096	0.086600	-0.035706
+9.870137	0.011970	0.021546	9.815576	0.047164	0.087266	-0.033841
+9.871187	-0.050275	0.009576	9.782060	0.045299	0.087533	-0.036505
+9.872178	-0.028729	-0.021546	9.887397	0.047430	0.090464	-0.037571
+9.873115	0.021546	-0.002394	9.851487	0.049828	0.089265	-0.035040
+9.874179	0.028729	-0.019152	9.875427	0.048496	0.088466	-0.037571
+9.875141	0.026334	-0.076609	9.841911	0.046231	0.089132	-0.038504
+9.876115	-0.021546	0.002394	9.837123	0.044233	0.089132	-0.036639
+9.877172	0.026334	0.026334	9.832334	0.046498	0.089398	-0.034907
+9.878140	0.007182	-0.047881	9.738967	0.048363	0.088332	-0.034640
+9.879178	0.002394	0.002394	9.777271	0.047564	0.085801	-0.035173
+9.880178	0.038305	-0.028729	9.772483	0.048363	0.086734	-0.036372
+9.881164	0.052669	0.004788	9.806000	0.049162	0.088466	-0.035040
+9.882192	0.038305	0.021546	9.863457	0.048896	0.087533	-0.037305
+9.883178	0.031123	-0.031123	9.829940	0.046897	0.089132	-0.039969
+9.884178	0.033517	-0.016758	9.784454	0.045965	0.090597	-0.042368
+9.885107	0.019152	-0.004788	9.849093	0.044233	0.091263	-0.038371
+9.886087	0.019152	0.004788	9.813182	0.045299	0.089398	-0.038104
+9.887178	0.019152	0.014364	9.731785	0.047963	0.088199	-0.036372
+9.888132	0.000000	0.014364	9.841911	0.047830	0.086734	-0.035706
+9.889179	0.026334	-0.031123	9.870639	0.046897	0.088466	-0.035440
+9.890178	-0.019152	0.009576	9.815576	0.046364	0.086467	-0.034640
+9.891178	-0.023940	0.004788	9.875427	0.045832	0.084602	-0.032908
+9.892132	0.014364	0.038305	9.930490	0.048230	0.087000	-0.034374
+9.893198	0.038305	0.031123	9.760513	0.047963	0.090198	-0.037571
+9.894178	-0.033517	0.016758	9.707844	0.045165	0.088599	-0.036239
+9.895176	0.000000	-0.031123	9.777271	0.043167	0.083003	-0.036772
+9.896178	-0.035911	-0.026334	9.734179	0.045032	0.084602	-0.035440
+9.897135	0.004788	0.009576	9.844305	0.047430	0.086467	-0.036239
+9.898133	0.033517	0.021546	9.882609	0.050095	0.089398	-0.039836
+9.899131	0.000000	-0.021546	9.856275	0.050095	0.089931	-0.039037
+9.900118	-0.026334	-0.016758	9.904156	0.046631	0.087933	-0.033708
+9.901088	-0.004788	0.055063	9.820364	0.046364	0.087666	-0.035440
+9.902177	0.002394	0.050275	9.846699	0.045965	0.088998	-0.035972
+9.903178	0.043093	0.009576	9.803606	0.044499	0.089132	-0.035972
+9.904150	0.028729	-0.069427	9.791636	0.045832	0.088332	-0.035306
+9.905177	-0.035911	-0.023940	9.820364	0.048629	0.086067	-0.033708
+9.906178	-0.059851	-0.014364	9.774877	0.048363	0.088998	-0.031576
+9.907175	0.023940	-0.033517	9.803606	0.045965	0.089531	-0.035839
+9.908179	0.028729	-0.023940	9.820364	0.046631	0.087666	-0.038770
+9.909177	0.016758	-0.031123	9.731785	0.047564	0.088998	-0.038237
+9.910179	0.004788	-0.011970	9.703056	0.047430	0.088332	-0.038237
+9.911156	-0.004788	-0.021546	9.743755	0.045299	0.088865	-0.036772
+9.912177	-0.019152	0.004788	9.849093	0.047297	0.086334	-0.038237
+9.913138	-0.007182	0.014364	9.887397	0.049429	0.085135	-0.040902
+9.914175	0.052669	0.035911	9.777271	0.049562	0.085401	-0.038104
+9.915177	0.076609	-0.007182	9.784454	0.046231	0.086867	-0.034507
+9.916171	0.050275	0.000000	9.719814	0.044899	0.084868	-0.037038
+9.917105	-0.009576	-0.004788	9.794030	0.045165	0.084868	-0.038904
+9.918086	0.007182	-0.028729	9.789242	0.045698	0.086067	-0.033841
+9.919089	0.038305	0.019152	9.726997	0.045299	0.086067	-0.035040
+9.920124	0.055063	0.000000	9.839517	0.046897	0.087000	-0.039303
+9.921179	0.076609	0.045487	9.810788	0.045698	0.088066	-0.039303
+9.922178	0.055063	0.007182	9.837123	0.045698	0.086734	-0.035706
+9.923141	0.038305	-0.040699	9.832334	0.046098	0.089265	-0.033974
+9.924145	0.047881	0.007182	9.817970	0.045565	0.089132	-0.034640
+9.925165	-0.035911	0.007182	9.913732	0.047564	0.087799	-0.036639
+9.926174	-0.062245	0.033517	9.882609	0.048096	0.087666	-0.037438
+9.927178	0.028729	0.055063	9.837123	0.048230	0.089132	-0.037172
+9.928173	0.021546	-0.045487	9.753331	0.047164	0.088865	-0.037971
+9.929179	-0.011970	-0.079003	9.782060	0.045299	0.089665	-0.036639
+9.930174	0.043093	-0.040699	9.834729	0.046231	0.088865	-0.034507
+9.931179	0.031123	-0.033517	9.767695	0.047164	0.087799	-0.035839
+9.932177	0.019152	0.002394	9.774877	0.048496	0.088998	-0.038504
+9.933166	0.009576	0.028729	9.794030	0.045165	0.089132	-0.039037
+9.934167	0.059851	0.007182	9.779666	0.045432	0.088199	-0.037172
+9.935186	0.031123	-0.035911	9.770089	0.048096	0.085534	-0.033841
+9.936177	-0.016758	0.002394	9.806000	0.046897	0.086467	-0.029977
+9.937137	-0.004788	0.021546	9.889792	0.045165	0.086467	-0.031709
+9.938129	0.016758	0.047881	9.875427	0.045165	0.087266	-0.035573
+9.939132	-0.014364	0.067033	9.801212	0.045032	0.087933	-0.034240
+9.940135	-0.019152	0.011970	9.899368	0.044632	0.087533	-0.036639
+9.941133	0.007182	-0.019152	9.832334	0.045299	0.090064	-0.038770
+9.942179	-0.031123	-0.002394	9.777271	0.048629	0.091397	-0.038104
+9.943178	-0.031123	-0.011970	9.877821	0.048363	0.090997	-0.037571
+9.944192	-0.007182	0.021546	9.803606	0.046631	0.090064	-0.036106
+9.945159	0.026334	0.035911	9.779666	0.047297	0.090997	-0.034907
+9.946179	0.033517	0.000000	9.849093	0.046364	0.089798	-0.035706
+9.947178	0.033517	0.009576	9.820364	0.045032	0.087799	-0.037172
+9.948176	0.019152	-0.014364	9.822758	0.044366	0.087400	-0.036639
+9.949147	0.033517	-0.026334	9.760513	0.044766	0.087133	-0.037971
+9.950112	0.050275	-0.014364	9.743755	0.047963	0.086867	-0.037704
+9.951172	0.083792	-0.011970	9.722208	0.049429	0.086734	-0.037038
+9.952178	0.040699	-0.016758	9.736573	0.047297	0.088199	-0.038104
+9.953178	0.004788	0.019152	9.827546	0.046231	0.086334	-0.037971
+9.954173	0.050275	0.002394	9.820364	0.046231	0.086600	-0.035839
+9.955197	0.043093	-0.023940	9.887397	0.046897	0.087266	-0.032908
+9.956171	-0.007182	-0.067033	9.865851	0.047830	0.086600	-0.035706
+9.957174	0.007182	-0.043093	9.822758	0.045965	0.086067	-0.035040
+9.958107	0.028729	0.007182	9.834729	0.048230	0.084602	-0.036372
+9.959196	0.038305	-0.038305	9.870639	0.048096	0.086334	-0.037172
+9.960176	0.028729	-0.019152	9.815576	0.045832	0.088466	-0.039436
+9.961174	0.026334	-0.035911	9.798818	0.045432	0.090064	-0.041035
+9.962177	0.019152	-0.059851	9.784454	0.042900	0.088066	-0.036772
+9.963175	0.002394	-0.021546	9.834729	0.043700	0.086600	-0.037838
+9.964140	0.014364	0.000000	9.849093	0.046364	0.086201	-0.038770
+9.965140	0.000000	0.007182	9.863457	0.049296	0.086201	-0.036772
+9.966179	-0.014364	-0.059851	9.806000	0.048363	0.085801	-0.036106
+9.967174	-0.007182	-0.050275	9.834729	0.049029	0.086334	-0.039303
+9.968169	0.021546	-0.014364	9.803606	0.045032	0.088998	-0.038904
+9.969131	0.009576	0.028729	9.825152	0.046231	0.090198	-0.037571
+9.970114	-0.014364	0.021546	9.827546	0.046631	0.090198	-0.034374
+9.971111	0.057457	0.071821	9.841911	0.045965	0.088732	-0.032109
+9.972111	0.038305	-0.002394	9.863457	0.045032	0.087533	-0.034374
+9.973114	0.011970	-0.028729	9.839517	0.046764	0.087000	-0.038904
+9.974159	0.045487	-0.019152	9.846699	0.045032	0.086467	-0.039170
+9.975133	0.009576	0.009576	9.858669	0.045032	0.087266	-0.035440
+9.976112	0.007182	0.016758	9.815576	0.045565	0.087666	-0.034507
+9.977175	0.004788	-0.028729	9.796424	0.049429	0.091263	-0.037305
+9.978134	-0.052669	-0.011970	9.731785	0.050228	0.089931	-0.039170
+9.979150	0.038305	-0.033517	9.794030	0.047963	0.089798	-0.036239
+9.980129	0.023940	-0.019152	9.813182	0.047031	0.090997	-0.038504
+9.981177	0.062245	-0.004788	9.801212	0.046098	0.090198	-0.036639
+9.982172	0.040699	0.026334	9.760513	0.047164	0.086600	-0.037172
+9.983175	-0.004788	0.007182	9.815576	0.047963	0.087266	-0.038237
+9.984177	-0.033517	-0.004788	9.806000	0.047830	0.086067	-0.033974
+9.985135	0.076609	0.016758	9.738967	0.048230	0.087000	-0.032109
+9.986157	0.043093	-0.026334	9.738967	0.048363	0.089132	-0.033841
+9.987150	0.002394	-0.002394	9.777271	0.048230	0.088599	-0.038237
+9.988118	-0.019152	-0.026334	9.856275	0.048496	0.089931	-0.037838
+9.989130	0.067033	-0.057457	9.806000	0.048096	0.090331	-0.035173
+9.990131	0.088580	-0.033517	9.851487	0.046498	0.089665	-0.035040
+9.991129	-0.019152	-0.009576	9.806000	0.047031	0.086201	-0.036239
+9.992129	0.016758	0.016758	9.875427	0.049562	0.085135	-0.038504
+9.993131	-0.007182	0.019152	9.841911	0.047164	0.088599	-0.035306
+9.994125	-0.004788	0.000000	9.810788	0.045698	0.090997	-0.037838
+9.995128	0.011970	0.028729	9.738967	0.046631	0.089398	-0.039570
+9.996111	-0.026334	-0.007182	9.837123	0.046631	0.087666	-0.037038
+9.997107	-0.095762	-0.023940	9.846699	0.048363	0.089531	-0.034640
+9.998107	-0.021546	-0.019152	9.693480	0.047697	0.088599	-0.034507
+9.999092	0.021546	-0.028729	9.755725	0.047697	0.087533	-0.033708
+10.000146	0.014364	-0.033517	9.806000	0.047963	0.089398	-0.033308
+10.001130	0.028729	-0.074215	9.803606	0.046498	0.089798	-0.036372
+10.002129	0.040699	-0.038305	9.770089	0.048363	0.088732	-0.036239
+10.003129	0.016758	-0.002394	9.849093	0.047164	0.088732	-0.035573
+10.004097	-0.011970	-0.043093	9.870639	0.045565	0.087799	-0.036239
+10.005097	-0.038305	-0.055063	9.861063	0.047697	0.089531	-0.037704
+10.006094	-0.004788	0.016758	9.798818	0.047297	0.090997	-0.036106
+10.007093	0.002394	0.047881	9.806000	0.046498	0.089665	-0.035306
+10.008093	-0.045487	-0.045487	9.810788	0.047297	0.088466	-0.035440
+10.009125	-0.004788	0.007182	9.803606	0.046498	0.088599	-0.037038
+10.010176	-0.014364	-0.007182	9.758119	0.045832	0.088998	-0.035839
+10.011129	-0.016758	-0.011970	9.774877	0.049429	0.089798	-0.034507
+10.012171	-0.038305	0.007182	9.777271	0.049162	0.088066	-0.034507
+10.013177	-0.031123	-0.004788	9.789242	0.047830	0.086067	-0.033441
+10.014176	-0.009576	-0.021546	9.746149	0.046897	0.087533	-0.034240
+10.015176	0.007182	-0.014364	9.750937	0.046764	0.090331	-0.034374
+10.016175	-0.023940	-0.023940	9.868245	0.044899	0.089531	-0.037438
+10.017175	0.055063	0.043093	9.772483	0.045565	0.086867	-0.033974
+10.018145	0.081397	0.004788	9.774877	0.046498	0.085135	-0.033974
+10.019116	0.040699	-0.007182	9.813182	0.046231	0.087266	-0.035306
+10.020169	0.011970	0.016758	9.834729	0.044899	0.089265	-0.037305
+10.021155	-0.021546	0.000000	9.868245	0.046098	0.092196	-0.038504
+10.022186	-0.002394	-0.007182	9.784454	0.048896	0.091263	-0.035040
+10.023175	0.016758	-0.023940	9.865851	0.049695	0.088066	-0.032908
+10.024138	-0.023940	-0.011970	9.832334	0.047564	0.088466	-0.035306
+10.025151	-0.043093	0.000000	9.798818	0.047164	0.086734	-0.038237
+10.026176	-0.064639	0.014364	9.798818	0.047697	0.086867	-0.037571
+10.027175	-0.047881	0.009576	9.796424	0.048230	0.086467	-0.035173
+10.028118	0.040699	-0.059851	9.755725	0.050095	0.086201	-0.034240
+10.029169	0.031123	0.011970	9.770089	0.048496	0.087933	-0.036239
+10.030176	-0.016758	0.002394	9.827546	0.048230	0.087533	-0.036772
+10.031130	0.002394	0.021546	9.806000	0.046231	0.089531	-0.038904
+10.032194	0.040699	-0.004788	9.777271	0.047164	0.088199	-0.037172
+10.033175	0.033517	-0.011970	9.856275	0.048230	0.087933	-0.035173
+10.034176	-0.002394	-0.011970	9.911338	0.047164	0.090464	-0.037571
+10.035116	0.021546	0.009576	9.806000	0.045432	0.086600	-0.037038
+10.036174	0.016758	0.031123	9.846699	0.044100	0.086467	-0.036106
+10.037149	-0.021546	0.026334	9.827546	0.047297	0.086067	-0.037305
+10.038176	0.035911	-0.014364	9.834729	0.048629	0.088998	-0.037571
+10.039175	-0.011970	-0.014364	9.827546	0.047564	0.090331	-0.038770
+10.040176	-0.047881	-0.045487	9.782060	0.047297	0.087533	-0.036106
+10.041165	0.009576	0.002394	9.772483	0.048363	0.088466	-0.035972
+10.042164	-0.009576	-0.004788	9.822758	0.047430	0.086734	-0.035972
+10.043116	-0.004788	-0.067033	9.789242	0.048096	0.086734	-0.035040
+10.044116	0.004788	-0.031123	9.734179	0.048896	0.089665	-0.035173
+10.045105	-0.002394	-0.016758	9.760513	0.048096	0.087533	-0.035706
+10.046176	-0.007182	-0.028729	9.865851	0.049029	0.087933	-0.036772
+10.047175	-0.038305	0.004788	9.841911	0.046364	0.088199	-0.039570
+10.048170	-0.002394	0.047881	9.758119	0.044366	0.088332	-0.037571
+10.049152	-0.011970	-0.007182	9.753331	0.044899	0.087133	-0.035173
+10.050117	0.028729	-0.009576	9.837123	0.045698	0.087400	-0.037971
+10.051109	-0.014364	-0.038305	9.806000	0.045565	0.087533	-0.036639
+10.052175	0.038305	-0.026334	9.743755	0.045698	0.088066	-0.036372
+10.053151	0.023940	-0.033517	9.782060	0.044100	0.087133	-0.035173
+10.054139	0.004788	-0.047881	9.794030	0.046364	0.089398	-0.034507
+10.055178	-0.004788	-0.004788	9.791636	0.046098	0.087933	-0.035440
+10.056172	0.007182	0.014364	9.772483	0.048230	0.086734	-0.036639
+10.057152	-0.019152	0.035911	9.820364	0.048230	0.088732	-0.034374
+10.058179	0.023940	-0.031123	9.741361	0.050095	0.087533	-0.034773
+10.059165	0.019152	0.000000	9.741361	0.047830	0.089665	-0.037038
+10.060124	0.021546	0.023940	9.770089	0.044899	0.090464	-0.035440
+10.061129	0.014364	-0.019152	9.712632	0.045032	0.087400	-0.034240
+10.062130	-0.031123	-0.026334	9.750937	0.047031	0.088199	-0.035440
+10.063174	0.011970	0.047881	9.779666	0.047297	0.090730	-0.037305
+10.064174	0.028729	0.026334	9.810788	0.048096	0.089798	-0.035839
+10.065120	0.038305	0.004788	9.803606	0.045432	0.089665	-0.038371
+10.066194	0.026334	-0.023940	9.782060	0.042900	0.089531	-0.036772
+10.067175	-0.009576	-0.021546	9.837123	0.045698	0.087933	-0.036772
+10.068174	0.004788	0.028729	9.817970	0.049429	0.088066	-0.036772
+10.069174	0.007182	0.004788	9.863457	0.050095	0.087000	-0.038904
+10.070176	0.035911	0.050275	9.734179	0.049828	0.088332	-0.036639
+10.071175	0.040699	-0.019152	9.734179	0.046098	0.088466	-0.032908
+10.072174	0.043093	-0.031123	9.808394	0.045565	0.087799	-0.034507
+10.073151	0.002394	0.023940	9.753331	0.047297	0.084469	-0.036505
+10.074187	0.019152	0.011970	9.798818	0.046098	0.085002	-0.036505
+10.075186	0.055063	0.026334	9.863457	0.047697	0.088599	-0.037838
+10.076220	-0.026334	0.023940	9.782060	0.047963	0.089798	-0.037571
+10.077170	-0.002394	-0.038305	9.755725	0.049562	0.088466	-0.038371
+10.078188	-0.079003	-0.045487	9.815576	0.050361	0.089531	-0.037438
+10.079231	0.014364	0.002394	9.858669	0.046098	0.088865	-0.034640
+10.080231	0.047881	-0.043093	9.820364	0.045432	0.089531	-0.034507
+10.081207	0.035911	-0.047881	9.703056	0.045698	0.089398	-0.034640
+10.082234	0.050275	0.002394	9.755725	0.047297	0.088865	-0.035706
+10.083171	0.090974	-0.040699	9.849093	0.049296	0.088865	-0.035440
+10.084142	0.007182	-0.071821	9.815576	0.046764	0.088066	-0.033841
+10.085147	0.002394	-0.069427	9.817970	0.046231	0.089132	-0.035040
+10.086113	-0.009576	-0.038305	9.784454	0.044632	0.088998	-0.037704
+10.087117	0.000000	-0.045487	9.755725	0.045565	0.086067	-0.037038
+10.088258	-0.009576	-0.047881	9.832334	0.048629	0.084735	-0.035040
+10.089143	0.000000	-0.011970	9.815576	0.048763	0.087400	-0.036772
+10.090156	0.059851	0.016758	9.817970	0.045698	0.087933	-0.037838
+10.091135	0.033517	0.031123	9.837123	0.045165	0.086467	-0.036239
+10.092164	0.047881	-0.002394	9.798818	0.045299	0.085002	-0.037172
+10.093155	0.014364	0.031123	9.815576	0.046364	0.086867	-0.034107
+10.094132	0.050275	-0.021546	9.743755	0.047164	0.087133	-0.033441
+10.095143	-0.011970	-0.033517	9.803606	0.047830	0.087000	-0.033708
+10.096080	0.009576	-0.016758	9.736573	0.045032	0.087799	-0.034907
+10.097148	-0.016758	-0.026334	9.765301	0.045299	0.087400	-0.038104
+10.098077	0.035911	0.009576	9.707844	0.047164	0.088732	-0.040769
+10.099091	0.045487	0.002394	9.741361	0.047830	0.087400	-0.037838
+10.100141	0.038305	0.043093	9.705450	0.046098	0.087000	-0.036372
+10.101168	-0.002394	0.007182	9.748543	0.046631	0.087400	-0.036639
+10.102126	-0.016758	-0.014364	9.767695	0.045299	0.086201	-0.039570
+10.103168	0.028729	-0.004788	9.762907	0.045698	0.083136	-0.036505
+10.104168	0.002394	-0.040699	9.846699	0.045965	0.083669	-0.032375
+10.105173	-0.033517	0.031123	9.834729	0.047963	0.086067	-0.034773
+10.106138	-0.014364	0.033517	9.913732	0.048763	0.088599	-0.036772
+10.107205	0.007182	0.021546	9.877821	0.047430	0.088599	-0.037571
+10.108207	-0.007182	-0.023940	9.741361	0.047830	0.088865	-0.040502
+10.109160	-0.038305	0.002394	9.815576	0.049029	0.090198	-0.035839
+10.110117	-0.028729	-0.004788	9.813182	0.048096	0.088732	-0.037838
+10.111206	0.038305	-0.038305	9.815576	0.046764	0.085668	-0.041302
+10.112205	0.062245	-0.021546	9.810788	0.046498	0.087000	-0.036505
+10.113207	0.000000	-0.002394	9.832334	0.048096	0.088599	-0.034773
+10.114206	0.021546	0.023940	9.722208	0.049828	0.087799	-0.037571
+10.115138	0.026334	-0.019152	9.760513	0.045698	0.087400	-0.035440
+10.116203	0.028729	0.002394	9.849093	0.044366	0.086867	-0.035839
+10.117212	0.009576	0.002394	9.791636	0.046364	0.088599	-0.037838
+10.118108	0.033517	0.016758	9.750937	0.044899	0.087533	-0.035573
+10.119108	-0.011970	0.043093	9.734179	0.045832	0.086201	-0.030776
+10.120133	0.009576	-0.004788	9.741361	0.045698	0.086067	-0.031975
+10.121140	0.076609	-0.014364	9.796424	0.046764	0.086734	-0.033308
+10.122143	0.055063	-0.019152	9.782060	0.047031	0.087666	-0.035306
+10.123138	0.079003	0.007182	9.853881	0.045165	0.085534	-0.035440
+10.124142	0.011970	0.004788	9.861063	0.046231	0.085401	-0.034240
+10.125135	0.004788	0.014364	9.844305	0.045165	0.085801	-0.036372
+10.126189	0.045487	-0.019152	9.772483	0.043433	0.086600	-0.035440
+10.127111	-0.019152	0.007182	9.817970	0.047963	0.091397	-0.035706
+10.128113	-0.007182	-0.011970	9.750937	0.046764	0.089798	-0.037172
+10.129147	0.057457	-0.038305	9.820364	0.048363	0.089798	-0.036772
+10.130143	0.011970	-0.038305	9.794030	0.050628	0.090597	-0.033841
+10.131139	-0.007182	-0.081397	9.825152	0.049029	0.088732	-0.033574
+10.132139	0.023940	-0.040699	9.782060	0.047430	0.083802	-0.037172
+10.133140	-0.004788	-0.026334	9.794030	0.048496	0.084868	-0.038237
+10.134142	0.016758	-0.045487	9.834729	0.049162	0.086467	-0.033441
+10.135132	0.016758	-0.062245	9.820364	0.049029	0.087133	-0.034107
+10.136129	0.007182	-0.050275	9.853881	0.050495	0.089665	-0.037971
+10.137159	0.016758	0.026334	9.822758	0.047430	0.091663	-0.038237
+10.138122	0.016758	0.038305	9.849093	0.044233	0.087933	-0.038504
+10.139136	-0.011970	0.026334	9.782060	0.044499	0.086867	-0.038237
+10.140136	0.019152	0.023940	9.777271	0.045832	0.088732	-0.036239
+10.141140	0.021546	-0.014364	9.849093	0.045565	0.087133	-0.033841
+10.142144	-0.007182	-0.009576	9.806000	0.045432	0.086467	-0.036106
+10.143205	-0.002394	-0.047881	9.839517	0.045165	0.085801	-0.036505
+10.144208	0.009576	-0.033517	9.731785	0.044233	0.086600	-0.039436
+10.145160	0.059851	0.002394	9.791636	0.042368	0.086867	-0.039703
+10.146162	0.062245	0.009576	9.813182	0.042634	0.087000	-0.038237
+10.147208	0.052669	-0.004788	9.794030	0.044766	0.088732	-0.035173
+10.148205	0.009576	-0.016758	9.803606	0.048096	0.088998	-0.036505
+10.149147	0.019152	-0.050275	9.827546	0.048363	0.085002	-0.033841
+10.150162	0.057457	-0.081397	9.844305	0.047963	0.085534	-0.033175
+10.151167	0.038305	-0.067033	9.767695	0.047963	0.088199	-0.034773
+10.152206	0.026334	-0.090974	9.782060	0.047164	0.088332	-0.037838
+10.153206	0.002394	-0.023940	9.813182	0.045965	0.088998	-0.039436
+10.154161	-0.019152	0.011970	9.861063	0.045965	0.088466	-0.036772
+10.155199	0.059851	0.026334	9.789242	0.049296	0.088998	-0.035839
+10.156203	0.009576	0.009576	9.825152	0.048896	0.088732	-0.036639
+10.157150	0.016758	0.026334	9.822758	0.048629	0.087266	-0.038904
+10.158150	0.028729	-0.043093	9.779666	0.047164	0.086201	-0.037438
+10.159172	0.033517	-0.047881	9.789242	0.044632	0.085934	-0.036505
+10.160205	0.000000	0.014364	9.827546	0.046098	0.088732	-0.037704
+10.161206	-0.011970	0.004788	9.806000	0.047830	0.087533	-0.035972
+10.162177	0.026334	0.002394	9.817970	0.048629	0.087933	-0.035173
+10.163156	0.021546	0.026334	9.829940	0.045698	0.088466	-0.035972
+10.164200	-0.016758	0.043093	9.837123	0.044899	0.087266	-0.038237
+10.165201	-0.023940	0.004788	9.875427	0.046631	0.086867	-0.038104
+10.166143	-0.035911	0.002394	9.736573	0.047430	0.087666	-0.039570
+10.167142	0.000000	0.016758	9.736573	0.044233	0.087799	-0.037438
+10.168203	0.011970	0.019152	9.825152	0.046231	0.088199	-0.034640
+10.169139	0.038305	0.057457	9.834729	0.046631	0.087266	-0.033708
+10.170209	0.019152	0.016758	9.772483	0.045032	0.088199	-0.036639
+10.171160	0.021546	0.016758	9.753331	0.046098	0.088998	-0.038237
+10.172183	0.043093	0.026334	9.782060	0.047963	0.086067	-0.037704
+10.173206	0.009576	-0.007182	9.858669	0.049162	0.083936	-0.035972
+10.174208	0.016758	-0.009576	9.844305	0.048230	0.088199	-0.036905
+10.175205	-0.007182	0.052669	9.837123	0.047164	0.091530	-0.037571
+10.176162	-0.031123	0.026334	9.813182	0.046498	0.088332	-0.040236
+10.177206	0.062245	0.002394	9.803606	0.046498	0.087000	-0.037305
+10.178208	0.055063	0.016758	9.806000	0.045965	0.087799	-0.036239
+10.179144	0.052669	-0.028729	9.808394	0.047697	0.088466	-0.035440
+10.180160	-0.016758	-0.067033	9.791636	0.047164	0.087266	-0.035972
+10.181162	-0.023940	0.002394	9.863457	0.046631	0.085668	-0.035839
+10.182207	-0.035911	-0.016758	9.810788	0.046231	0.088865	-0.036772
+10.183205	-0.007182	-0.004788	9.777271	0.044499	0.090331	-0.036772
+10.184203	-0.023940	-0.031123	9.779666	0.046098	0.091530	-0.033574
+10.185135	-0.007182	-0.038305	9.806000	0.047164	0.090997	-0.037571
+10.186205	0.016758	0.004788	9.784454	0.047830	0.091130	-0.040103
+10.187158	0.040699	0.009576	9.758119	0.046498	0.089531	-0.037172
+10.188114	0.009576	0.019152	9.777271	0.045832	0.085534	-0.038637
+10.189120	-0.002394	-0.016758	9.858669	0.044366	0.086867	-0.037038
+10.190134	0.019152	0.016758	9.923308	0.046364	0.087133	-0.035306
+10.191139	0.059851	-0.004788	9.784454	0.048763	0.086334	-0.034640
+10.192140	0.009576	-0.028729	9.772483	0.047031	0.085135	-0.035573
+10.193143	-0.019152	-0.021546	9.820364	0.045698	0.086467	-0.036372
+10.194143	0.007182	-0.004788	9.784454	0.046231	0.089132	-0.035040
+10.195139	0.009576	-0.031123	9.801212	0.047830	0.091796	-0.038237
+10.196139	0.052669	-0.004788	9.808394	0.045432	0.089398	-0.037305
+10.197140	0.026334	-0.011970	9.885003	0.046098	0.089931	-0.035173
+10.198142	0.004788	-0.038305	9.942460	0.048363	0.091663	-0.037305
+10.199123	0.016758	-0.055063	9.827546	0.046764	0.088599	-0.039703
+10.200179	0.000000	-0.035911	9.803606	0.047297	0.085668	-0.040769
+10.201159	-0.028729	-0.014364	9.841911	0.048230	0.087533	-0.039170
+10.202138	-0.045487	-0.043093	9.779666	0.047963	0.087933	-0.036372
+10.203204	-0.033517	-0.033517	9.710238	0.046631	0.086600	-0.037305
+10.204203	-0.009576	0.019152	9.770089	0.045832	0.088066	-0.037704
+10.205206	-0.004788	-0.007182	9.837123	0.046364	0.089132	-0.035972
+10.206209	-0.014364	-0.031123	9.770089	0.047430	0.090198	-0.036239
+10.207143	-0.007182	-0.057457	9.722208	0.048230	0.089132	-0.038504
+10.208204	0.023940	-0.033517	9.827546	0.048896	0.089265	-0.037704
+10.209141	0.033517	-0.035911	9.798818	0.048896	0.088865	-0.036639
+10.210162	0.043093	-0.028729	9.779666	0.049296	0.089132	-0.033974
+10.211198	0.033517	-0.011970	9.760513	0.046231	0.090331	-0.035972
+10.212123	0.052669	-0.035911	9.755725	0.049029	0.090331	-0.034773
+10.213203	0.081397	0.014364	9.767695	0.047564	0.089665	-0.037038
+10.214121	0.026334	0.040699	9.779666	0.045965	0.087799	-0.035972
+10.215127	0.014364	0.038305	9.801212	0.045299	0.086334	-0.035573
+10.216108	0.011970	0.014364	9.722208	0.046364	0.087266	-0.033974
+10.217133	-0.031123	0.007182	9.779666	0.047564	0.088732	-0.037038
+10.218133	-0.011970	0.014364	9.825152	0.046631	0.085801	-0.036639
+10.219202	-0.023940	-0.016758	9.849093	0.045565	0.083802	-0.033708
+10.220136	-0.009576	-0.050275	9.827546	0.046364	0.087000	-0.032508
+10.221131	0.002394	0.007182	9.801212	0.048763	0.088332	-0.032908
+10.222208	-0.031123	-0.002394	9.813182	0.049029	0.088998	-0.034374
+10.223197	0.011970	0.023940	9.777271	0.047963	0.089398	-0.035972
+10.224139	-0.009576	0.023940	9.750937	0.047164	0.089265	-0.036505
+10.225089	-0.016758	0.014364	9.794030	0.045832	0.088599	-0.039836
+10.226138	0.019152	0.007182	9.736573	0.045432	0.087400	-0.036106
+10.227111	-0.014364	-0.014364	9.746149	0.048230	0.087133	-0.035040
+10.228102	0.028729	-0.055063	9.741361	0.047031	0.087000	-0.036772
+10.229132	0.093368	-0.023940	9.865851	0.046231	0.087266	-0.037838
+10.230162	0.055063	-0.004788	9.801212	0.049429	0.088599	-0.040769
+10.231197	-0.028729	-0.009576	9.719814	0.050095	0.088332	-0.040103
+10.232143	-0.009576	-0.002394	9.892186	0.050894	0.087000	-0.037571
+10.233203	-0.028729	-0.055063	9.882609	0.047830	0.088599	-0.034773
+10.234146	0.000000	0.000000	9.803606	0.045698	0.088066	-0.032242
+10.235105	-0.007182	-0.016758	9.834729	0.048496	0.088199	-0.032242
+10.236206	-0.035911	0.035911	9.806000	0.048629	0.088066	-0.034107
+10.237164	-0.016758	0.055063	9.858669	0.048096	0.088599	-0.036639
+10.238147	-0.009576	0.011970	9.875427	0.047564	0.092462	-0.035972
+10.239170	0.028729	-0.007182	9.839517	0.046764	0.091796	-0.036905
+10.240160	0.002394	-0.043093	9.789242	0.046631	0.087000	-0.035972
+10.241204	0.043093	0.000000	9.782060	0.046631	0.085002	-0.037038
+10.242144	0.009576	0.043093	9.736573	0.047564	0.085268	-0.038237
+10.243141	0.033517	0.007182	9.794030	0.046098	0.087533	-0.035573
+10.244140	-0.021546	-0.028729	9.806000	0.046098	0.087266	-0.036772
+10.245202	0.004788	0.007182	9.791636	0.047031	0.086334	-0.037704
+10.246205	0.016758	0.081397	9.806000	0.048363	0.085668	-0.038371
+10.247202	0.016758	-0.009576	9.734179	0.049962	0.087666	-0.032775
+10.248161	-0.055063	-0.028729	9.760513	0.048096	0.089931	-0.031842
+10.249145	0.028729	0.002394	9.815576	0.045698	0.088865	-0.036372
+10.250134	0.086186	0.038305	9.834729	0.046631	0.090730	-0.036505
+10.251117	0.067033	0.026334	9.863457	0.048496	0.088332	-0.036639
+10.252202	0.050275	-0.023940	9.786848	0.049162	0.086734	-0.036505
+10.253202	0.007182	-0.023940	9.789242	0.049029	0.087933	-0.036905
+10.254208	-0.038305	-0.047881	9.827546	0.049162	0.088732	-0.036239
+10.255202	-0.031123	-0.031123	9.913732	0.047830	0.089398	-0.033441
+10.256203	-0.035911	0.040699	9.892186	0.046231	0.090064	-0.037172
+10.257205	0.033517	0.014364	9.777271	0.045698	0.090064	-0.036505
+10.258148	0.023940	0.023940	9.813182	0.045965	0.087666	-0.036239
+10.259116	0.038305	0.038305	9.777271	0.048230	0.088599	-0.038104
+10.260135	0.002394	0.004788	9.734179	0.050228	0.086600	-0.034107
+10.261130	0.019152	-0.019152	9.762907	0.048629	0.085135	-0.035839
+10.262118	0.026334	0.014364	9.789242	0.046764	0.085135	-0.038770
+10.263121	0.059851	-0.011970	9.803606	0.046631	0.085534	-0.036505
+10.264122	0.016758	-0.067033	9.750937	0.046897	0.085268	-0.036639
+10.265125	0.009576	-0.047881	9.715026	0.046764	0.087000	-0.035306
+10.266118	-0.011970	-0.007182	9.748543	0.046897	0.089398	-0.035173
+10.267122	-0.016758	0.045487	9.770089	0.047697	0.089665	-0.031975
+10.268121	-0.028729	0.026334	9.834729	0.047963	0.087933	-0.032508
+10.269165	-0.014364	-0.002394	9.753331	0.047430	0.088599	-0.035306
+10.270116	0.047881	-0.007182	9.782060	0.045832	0.088998	-0.035040
+10.271101	0.050275	-0.055063	9.791636	0.045299	0.087000	-0.035173
+10.272121	0.004788	-0.050275	9.789242	0.046231	0.085934	-0.034773
+10.273121	0.028729	-0.004788	9.774877	0.046897	0.087000	-0.038504
+10.274068	0.028729	0.021546	9.741361	0.048363	0.088998	-0.038237
+10.275067	0.014364	-0.016758	9.784454	0.048496	0.089398	-0.037971
+10.276065	0.014364	-0.019152	9.803606	0.049562	0.088599	-0.036905
+10.277065	0.019152	-0.009576	9.832334	0.048496	0.087533	-0.034374
+10.278066	-0.023940	0.055063	9.774877	0.045698	0.088998	-0.035573
+10.279066	0.007182	-0.007182	9.774877	0.044766	0.089531	-0.036372
+10.280065	0.055063	-0.002394	9.806000	0.043700	0.088066	-0.032375
+10.281067	0.026334	-0.031123	9.801212	0.044899	0.088998	-0.037305
+10.282064	0.009576	-0.019152	9.786848	0.046231	0.088865	-0.037038
+10.283065	-0.007182	-0.031123	9.774877	0.048496	0.087400	-0.036239
+10.284065	0.059851	-0.031123	9.765301	0.047031	0.087000	-0.039570
+10.285071	-0.007182	-0.035911	9.839517	0.046364	0.086734	-0.039436
+10.286066	-0.004788	-0.052669	9.829940	0.048496	0.087666	-0.035706
+10.287065	0.014364	-0.031123	9.851487	0.047963	0.088599	-0.036772
+10.288061	0.009576	-0.033517	9.777271	0.045965	0.088332	-0.036239
+10.289067	-0.021546	-0.045487	9.748543	0.043433	0.088466	-0.035839
+10.290066	-0.002394	0.000000	9.815576	0.047031	0.088199	-0.039570
+10.291066	0.040699	-0.040699	9.849093	0.048763	0.085401	-0.039436
+10.292063	-0.023940	-0.019152	9.839517	0.048230	0.086734	-0.036639
+10.293070	-0.028729	0.004788	9.786848	0.046098	0.089132	-0.032908
+10.294062	-0.009576	-0.009576	9.803606	0.044899	0.088599	-0.033175
+10.295062	0.009576	-0.009576	9.765301	0.045965	0.087533	-0.035040
+10.296065	0.026334	-0.038305	9.736573	0.049162	0.087666	-0.037038
+10.297070	0.043093	-0.081397	9.738967	0.048896	0.091130	-0.037704
+10.298055	0.090974	-0.074215	9.731785	0.048496	0.088332	-0.038770
+10.299062	0.040699	0.000000	9.875427	0.049962	0.086600	-0.038504
+10.300062	0.038305	0.009576	9.846699	0.048763	0.087799	-0.034640
+10.301075	0.014364	0.026334	9.877821	0.047830	0.087933	-0.033441
+10.302066	0.028729	0.028729	9.844305	0.046498	0.086734	-0.032375
+10.303065	0.076609	0.004788	9.944854	0.045032	0.089398	-0.034240
+10.304065	-0.011970	-0.043093	9.839517	0.050495	0.090198	-0.031443
+10.305067	-0.035911	-0.059851	9.758119	0.051427	0.088332	-0.034507
+10.306084	0.011970	-0.009576	9.839517	0.048896	0.085401	-0.039037
+10.307056	-0.002394	0.011970	9.813182	0.046897	0.085135	-0.037038
+10.308137	0.000000	0.011970	9.887397	0.046897	0.085268	-0.035706
+10.309146	0.016758	0.019152	9.820364	0.046498	0.086201	-0.036239
+10.310146	0.014364	0.033517	9.760513	0.047430	0.088066	-0.035440
+10.311145	-0.038305	0.000000	9.762907	0.049162	0.090331	-0.033974
+10.312115	-0.011970	-0.007182	9.810788	0.047164	0.088066	-0.034107
+10.313129	-0.016758	-0.021546	9.791636	0.046098	0.084602	-0.037438
+10.314146	0.007182	0.009576	9.784454	0.046498	0.086067	-0.034773
+10.315143	-0.007182	0.038305	9.863457	0.047031	0.089132	-0.034107
+10.316143	0.028729	-0.002394	9.796424	0.048763	0.090464	-0.035040
+10.317139	0.004788	0.004788	9.760513	0.047430	0.089265	-0.036505
+10.318131	0.011970	0.014364	9.762907	0.047031	0.087799	-0.035040
+10.319175	0.035911	0.019152	9.753331	0.047297	0.085534	-0.037038
+10.320174	0.076609	-0.014364	9.806000	0.045032	0.087933	-0.037438
+10.321175	0.014364	0.016758	9.839517	0.045032	0.086201	-0.034773
+10.322120	-0.007182	-0.011970	9.791636	0.046631	0.086067	-0.031576
+10.323132	-0.023940	-0.019152	9.758119	0.048096	0.087400	-0.033041
+10.324175	-0.004788	0.016758	9.861063	0.048363	0.087266	-0.041168
+10.325120	-0.011970	0.007182	9.849093	0.044100	0.087799	-0.039436
+10.326161	0.002394	0.026334	9.810788	0.043966	0.088332	-0.036772
+10.327161	-0.043093	0.031123	9.834729	0.046897	0.091263	-0.032375
+10.328141	-0.028729	0.035911	9.837123	0.048230	0.088998	-0.032109
+10.329204	0.050275	0.040699	9.841911	0.046498	0.087266	-0.031709
+10.330207	0.011970	-0.004788	9.829940	0.047564	0.088332	-0.033441
+10.331138	0.021546	-0.026334	9.803606	0.046231	0.089931	-0.038371
+10.332127	-0.002394	0.019152	9.882609	0.047297	0.090597	-0.038104
+10.333193	0.019152	0.009576	9.858669	0.048096	0.088998	-0.036505
+10.334204	-0.007182	-0.028729	9.820364	0.049029	0.089398	-0.036239
+10.335146	-0.004788	-0.064639	9.899368	0.048763	0.088732	-0.034907
+10.336201	0.035911	-0.043093	9.789242	0.049429	0.090730	-0.037704
+10.337167	0.035911	-0.062245	9.789242	0.049029	0.090198	-0.038904
+10.338144	0.028729	-0.067033	9.825152	0.047963	0.087400	-0.036505
+10.339203	-0.033517	-0.021546	9.755725	0.048629	0.086334	-0.036106
+10.340159	-0.004788	-0.023940	9.762907	0.047031	0.087133	-0.035440
+10.341159	0.002394	0.009576	9.798818	0.045432	0.087266	-0.034507
+10.342157	-0.011970	-0.004788	9.784454	0.044766	0.088332	-0.035040
+10.343202	0.035911	-0.028729	9.806000	0.048363	0.090198	-0.038237
+10.344173	0.031123	-0.031123	9.820364	0.047031	0.090064	-0.040902
+10.345203	-0.021546	-0.011970	9.844305	0.044899	0.087933	-0.037704
+10.346206	0.000000	-0.014364	9.712632	0.048096	0.083536	-0.032775
+10.347202	0.045487	-0.021546	9.762907	0.047564	0.083936	-0.033574
+10.348202	0.045487	-0.011970	9.815576	0.045565	0.087666	-0.034507
+10.349159	-0.014364	-0.011970	9.774877	0.049296	0.089798	-0.037438
+10.350160	-0.031123	-0.031123	9.760513	0.049029	0.088066	-0.037038
+10.351195	-0.016758	-0.014364	9.760513	0.044899	0.088865	-0.033974
+10.352136	0.014364	0.000000	9.853881	0.043433	0.091530	-0.032642
+10.353204	0.004788	0.031123	9.906550	0.046631	0.092196	-0.034240
+10.354204	-0.031123	0.009576	9.822758	0.048496	0.089398	-0.033974
+10.355170	-0.067033	0.031123	9.710238	0.046098	0.088599	-0.036772
+10.356204	0.021546	0.038305	9.772483	0.046231	0.088466	-0.035306
+10.357203	0.074215	0.004788	9.782060	0.045432	0.083802	-0.036505
+10.358173	0.011970	0.019152	9.834729	0.045299	0.085135	-0.036905
+10.359157	0.004788	-0.009576	9.796424	0.046631	0.086334	-0.037038
+10.360205	-0.059851	-0.028729	9.870639	0.048496	0.087799	-0.038371
+10.361159	-0.023940	0.000000	9.798818	0.047430	0.092196	-0.038237
+10.362206	-0.016758	-0.002394	9.839517	0.047697	0.090464	-0.041302
+10.363203	0.000000	0.009576	9.825152	0.047697	0.088466	-0.038637
+10.364163	0.002394	0.009576	9.844305	0.045965	0.087400	-0.033974
+10.365150	0.021546	0.019152	9.856275	0.045832	0.087000	-0.035173
+10.366207	0.052669	-0.038305	9.820364	0.046364	0.087266	-0.036772
+10.367208	0.031123	-0.011970	9.832334	0.047564	0.089265	-0.038904
+10.368161	-0.057457	0.045487	9.858669	0.050095	0.087666	-0.040103
+10.369202	-0.052669	0.035911	9.820364	0.048896	0.088332	-0.038504
+10.370161	-0.047881	0.035911	9.789242	0.043966	0.089265	-0.037305
+10.371204	-0.007182	0.074215	9.782060	0.043833	0.087933	-0.036772
+10.372203	0.011970	0.021546	9.798818	0.045165	0.088732	-0.037571
+10.373203	0.023940	0.002394	9.755725	0.045698	0.088199	-0.034374
+10.374206	0.076609	0.016758	9.760513	0.047830	0.087533	-0.035306
+10.375200	0.011970	-0.062245	9.806000	0.048629	0.088865	-0.033708
+10.376158	-0.047881	-0.050275	9.722208	0.047963	0.088332	-0.032908
+10.377160	-0.057457	-0.050275	9.813182	0.047564	0.089132	-0.035306
+10.378149	-0.045487	0.007182	9.832334	0.047963	0.089798	-0.040769
+10.379203	-0.047881	0.004788	9.794030	0.048230	0.092329	-0.039436
+10.380201	-0.035911	-0.002394	9.774877	0.047164	0.088466	-0.036505
+10.381155	0.026334	0.002394	9.774877	0.045032	0.087266	-0.034773
+10.382131	0.026334	0.000000	9.880215	0.043833	0.089132	-0.032908
+10.383165	-0.045487	0.011970	9.896974	0.047830	0.088599	-0.031576
+10.384134	-0.052669	-0.007182	9.825152	0.045832	0.087400	-0.034640
+10.385134	-0.014364	0.009576	9.806000	0.046764	0.087666	-0.037172
+10.386135	0.014364	-0.079003	9.726997	0.048363	0.087266	-0.039570
+10.387131	0.031123	-0.057457	9.755725	0.046364	0.086600	-0.035440
+10.388109	0.011970	-0.047881	9.822758	0.045165	0.087933	-0.034773
+10.389131	0.004788	0.000000	9.782060	0.045299	0.088865	-0.038637
+10.390134	0.038305	0.031123	9.782060	0.045299	0.090331	-0.038770
+10.391132	-0.019152	0.035911	9.858669	0.044233	0.088466	-0.035440
+10.392165	0.023940	-0.019152	9.877821	0.047164	0.087000	-0.030910
+10.393127	0.002394	-0.014364	9.849093	0.048896	0.089398	-0.035173
+10.394093	-0.040699	0.014364	9.791636	0.050628	0.088466	-0.039303
+10.395093	0.038305	0.047881	9.806000	0.051427	0.088466	-0.039570
+10.396089	0.031123	0.040699	9.870639	0.049296	0.088199	-0.035573
+10.397066	0.052669	0.009576	9.796424	0.049296	0.084868	-0.033441
+10.398111	0.076609	-0.047881	9.760513	0.047963	0.083936	-0.033974
+10.399088	0.035911	-0.016758	9.827546	0.047564	0.085002	-0.037838
+10.400103	0.035911	-0.033517	9.832334	0.048896	0.087133	-0.038371
+10.401150	0.004788	-0.040699	9.820364	0.047830	0.088332	-0.037971
+10.402132	-0.011970	0.028729	9.841911	0.046098	0.087000	-0.035972
+10.403147	0.019152	-0.031123	9.822758	0.047963	0.085135	-0.037305
+10.404138	-0.040699	-0.023940	9.738967	0.048763	0.086600	-0.037971
+10.405121	-0.076609	-0.064639	9.729391	0.048629	0.085934	-0.037305
+10.406155	-0.002394	0.016758	9.774877	0.045832	0.087666	-0.033574
+10.407131	-0.023940	-0.047881	9.782060	0.046897	0.088998	-0.033574
+10.408156	-0.040699	-0.019152	9.746149	0.048230	0.088199	-0.032908
+10.409137	0.045487	0.009576	9.779666	0.048629	0.087000	-0.034107
+10.410135	0.026334	-0.007182	9.724603	0.050495	0.087400	-0.033841
+10.411202	0.047881	-0.023940	9.808394	0.050228	0.086467	-0.032508
+10.412197	0.033517	0.007182	9.861063	0.048763	0.087666	-0.033574
+10.413200	0.021546	0.011970	9.820364	0.049029	0.090597	-0.034640
+10.414204	0.033517	0.014364	9.789242	0.047564	0.088865	-0.033175
+10.415201	0.014364	0.043093	9.820364	0.045565	0.087533	-0.035440
+10.416203	0.011970	-0.028729	9.846699	0.049828	0.091663	-0.037305
+10.417202	0.002394	-0.031123	9.906550	0.052493	0.090464	-0.038637
+10.418123	0.014364	-0.040699	9.913732	0.048496	0.089398	-0.038904
+10.419152	0.000000	-0.031123	9.889792	0.046498	0.086600	-0.035839
+10.420136	0.043093	0.004788	9.798818	0.048496	0.087933	-0.037305
+10.421151	0.004788	0.004788	9.798818	0.049162	0.088732	-0.036106
+10.422205	0.007182	0.011970	9.868245	0.046631	0.088066	-0.033175
+10.423202	0.011970	-0.014364	9.767695	0.045965	0.086067	-0.033841
+10.424202	0.007182	-0.033517	9.719814	0.046897	0.086334	-0.034907
+10.425161	-0.045487	-0.019152	9.659963	0.044766	0.088466	-0.037971
+10.426133	0.043093	0.040699	9.839517	0.045299	0.087666	-0.035706
+10.427127	-0.035911	0.021546	9.777271	0.048363	0.088865	-0.035173
+10.428129	-0.009576	0.004788	9.762907	0.048496	0.089531	-0.038637
+10.429113	0.026334	0.035911	9.729391	0.047963	0.087933	-0.038770
+10.430074	0.031123	-0.004788	9.784454	0.045299	0.085135	-0.036239
+10.431130	0.004788	-0.011970	9.794030	0.043034	0.086600	-0.034773
+10.432130	0.019152	-0.023940	9.782060	0.045165	0.088332	-0.038237
+10.433130	0.045487	-0.026334	9.853881	0.046231	0.087933	-0.037438
+10.434131	0.069427	0.002394	9.906550	0.045698	0.088332	-0.035573
+10.435107	0.009576	-0.009576	9.822758	0.047164	0.090730	-0.032375
+10.436094	-0.045487	-0.002394	9.810788	0.047963	0.088998	-0.034107
+10.437097	-0.028729	0.019152	9.844305	0.047164	0.090331	-0.036639
+10.438082	0.004788	0.009576	9.794030	0.046498	0.089931	-0.037172
+10.439097	0.000000	0.038305	9.729391	0.047564	0.088998	-0.037838
+10.440098	0.047881	-0.023940	9.719814	0.046897	0.085934	-0.035440
+10.441099	0.019152	0.009576	9.822758	0.048363	0.087133	-0.037438
+10.442053	-0.035911	-0.038305	9.832334	0.050361	0.088199	-0.040369
+10.443065	-0.047881	-0.040699	9.736573	0.047697	0.086867	-0.036505
+10.444063	0.000000	0.031123	9.784454	0.045299	0.087933	-0.033574
+10.445063	0.033517	0.007182	9.877821	0.045832	0.087000	-0.037038
+10.446063	0.045487	0.033517	9.892186	0.050228	0.085002	-0.039037
+10.447073	0.004788	0.009576	9.722208	0.048230	0.087000	-0.039436
+10.448085	0.050275	-0.023940	9.647993	0.046498	0.089132	-0.038104
+10.449065	0.045487	0.028729	9.755725	0.043700	0.091663	-0.035839
+10.450062	0.026334	0.069427	9.834729	0.047830	0.088998	-0.036505
+10.451060	0.035911	-0.016758	9.827546	0.050095	0.088998	-0.039170
+10.452063	0.019152	-0.007182	9.870639	0.048363	0.090730	-0.037704
+10.453060	0.026334	0.007182	9.755725	0.045032	0.088998	-0.037038
+10.454073	0.055063	-0.016758	9.794030	0.043833	0.086867	-0.039703
+10.455067	0.038305	0.002394	9.863457	0.047430	0.088199	-0.038371
+10.456069	0.021546	0.009576	9.798818	0.049162	0.087933	-0.036639
+10.457061	0.019152	-0.031123	9.674328	0.050361	0.086867	-0.036239
+10.458066	0.007182	-0.043093	9.722208	0.047564	0.086867	-0.038504
+10.459073	0.093368	0.011970	9.688692	0.046098	0.087799	-0.038371
+10.460068	0.067033	0.019152	9.726997	0.046231	0.092596	-0.036505
+10.461072	-0.023940	-0.031123	9.829940	0.047164	0.088732	-0.037305
+10.462073	-0.004788	-0.026334	9.887397	0.047564	0.084868	-0.038904
+10.463072	0.004788	-0.055063	9.820364	0.046364	0.084202	-0.034507
+10.464068	0.019152	-0.011970	9.808394	0.046897	0.086467	-0.034507
+10.465057	0.007182	0.028729	9.796424	0.045965	0.089132	-0.037438
+10.466076	-0.007182	0.023940	9.782060	0.046764	0.087666	-0.039836
+10.467077	-0.047881	-0.035911	9.832334	0.047164	0.086600	-0.036505
+10.468055	-0.064639	-0.059851	9.753331	0.049695	0.087266	-0.034240
+10.469044	-0.019152	-0.028729	9.858669	0.048629	0.089398	-0.039037
+10.470076	0.057457	-0.007182	9.834729	0.045832	0.092196	-0.038104
+10.471078	0.021546	-0.023940	9.772483	0.044632	0.089531	-0.037571
+10.472077	0.009576	0.014364	9.782060	0.044766	0.087666	-0.036772
+10.473077	-0.014364	-0.026334	9.841911	0.045299	0.083936	-0.034507
+10.474076	0.007182	0.038305	9.853881	0.044366	0.085801	-0.034107
+10.475076	-0.023940	0.019152	9.794030	0.044499	0.088332	-0.033974
+10.476077	-0.016758	-0.083792	9.827546	0.045698	0.092063	-0.031709
+10.477077	0.002394	-0.035911	9.813182	0.047164	0.090464	-0.034640
+10.478064	-0.004788	0.040699	9.822758	0.046764	0.088332	-0.035972
+10.479051	0.021546	0.016758	9.770089	0.046764	0.089132	-0.035573
+10.480063	0.016758	-0.011970	9.849093	0.044766	0.090864	-0.035306
+10.481059	0.011970	-0.014364	9.738967	0.044632	0.089398	-0.036239
+10.482059	-0.045487	-0.031123	9.683904	0.047164	0.087666	-0.038770
+10.483058	-0.081397	-0.023940	9.839517	0.045965	0.087799	-0.038770
+10.484058	0.004788	-0.062245	9.839517	0.047297	0.086600	-0.034507
+10.485042	0.050275	0.031123	9.853881	0.048896	0.088865	-0.031443
+10.486060	-0.023940	0.035911	9.789242	0.047963	0.088732	-0.037305
+10.487063	-0.035911	0.026334	9.801212	0.046897	0.089798	-0.040902
+10.488067	0.033517	-0.033517	9.863457	0.046364	0.088332	-0.040236
+10.489063	-0.016758	0.011970	9.839517	0.044233	0.086467	-0.038237
+10.490072	0.002394	0.038305	9.875427	0.045032	0.083270	-0.036106
+10.491117	0.067033	0.050275	9.827546	0.047164	0.086067	-0.038104
+10.492148	-0.007182	0.009576	9.846699	0.049429	0.087933	-0.038371
+10.493075	0.009576	-0.019152	9.851487	0.049828	0.087266	-0.034507
+10.494118	0.009576	-0.023940	9.832334	0.048230	0.088066	-0.032375
+10.495106	0.055063	-0.007182	9.786848	0.046231	0.087666	-0.032908
+10.496117	0.002394	0.057457	9.794030	0.043567	0.086600	-0.034640
+10.497143	-0.002394	0.033517	9.762907	0.044899	0.088066	-0.034107
+10.498098	-0.011970	0.021546	9.741361	0.045965	0.088466	-0.036239
+10.499147	0.021546	-0.011970	9.810788	0.046764	0.086734	-0.038637
+10.500149	0.014364	0.014364	9.863457	0.047564	0.088732	-0.038104
+10.501148	-0.074215	0.007182	9.839517	0.049029	0.088466	-0.037971
+10.502150	-0.038305	0.038305	9.791636	0.048896	0.088732	-0.036639
+10.503148	-0.004788	0.031123	9.813182	0.046631	0.089798	-0.033974
+10.504146	0.019152	-0.057457	9.820364	0.047297	0.088998	-0.037838
+10.505149	0.009576	-0.002394	9.772483	0.047697	0.089931	-0.036239
+10.506149	0.004788	0.117308	9.817970	0.045565	0.088732	-0.031576
+10.507103	0.035911	0.059851	9.825152	0.045432	0.087400	-0.033574
+10.508157	0.023940	-0.014364	9.786848	0.046631	0.087133	-0.037305
+10.509149	0.038305	-0.026334	9.772483	0.046231	0.086334	-0.036372
+10.510080	0.014364	0.004788	9.746149	0.046364	0.088066	-0.037571
+10.511148	0.009576	-0.004788	9.777271	0.046364	0.087666	-0.036505
+10.512148	0.004788	0.002394	9.760513	0.048230	0.088332	-0.033708
+10.513150	-0.023940	-0.016758	9.829940	0.048096	0.089398	-0.036106
+10.514122	0.033517	-0.004788	9.873033	0.046897	0.090864	-0.038371
+10.515103	0.093368	-0.007182	9.861063	0.045698	0.089531	-0.035440
+10.516150	0.035911	0.016758	9.772483	0.044100	0.087666	-0.035972
+10.517120	-0.033517	0.007182	9.767695	0.045032	0.087933	-0.036106
+10.518154	-0.004788	0.000000	9.806000	0.048629	0.088066	-0.034640
+10.519149	-0.009576	-0.021546	9.806000	0.050628	0.087933	-0.036905
+10.520148	0.047881	0.004788	9.820364	0.049962	0.087666	-0.035573
+10.521151	0.011970	-0.004788	9.813182	0.046231	0.088066	-0.035972
+10.522115	-0.007182	0.000000	9.853881	0.045565	0.087533	-0.034374
+10.523147	0.021546	0.007182	9.865851	0.046631	0.088332	-0.033574
+10.524150	0.007182	0.011970	9.834729	0.046631	0.087533	-0.034773
+10.525149	0.002394	-0.055063	9.825152	0.048230	0.085668	-0.037038
+10.526156	0.028729	-0.064639	9.808394	0.050095	0.086600	-0.037971
+10.527128	0.019152	0.009576	9.882609	0.049429	0.086734	-0.037438
+10.528122	0.081397	-0.023940	9.841911	0.049562	0.087000	-0.038637
+10.529149	0.028729	-0.014364	9.844305	0.047830	0.085002	-0.035440
+10.530133	0.040699	0.002394	9.846699	0.047031	0.087133	-0.037971
+10.531146	0.011970	0.007182	9.832334	0.046231	0.087799	-0.038237
+10.532073	0.011970	0.007182	9.834729	0.049162	0.086734	-0.036505
+10.533078	-0.026334	0.033517	9.817970	0.049029	0.088066	-0.034773
+10.534119	-0.016758	0.009576	9.779666	0.046498	0.086734	-0.034374
+10.535085	-0.004788	0.021546	9.822758	0.044366	0.086867	-0.032242
+10.536075	0.038305	-0.021546	9.791636	0.045032	0.087266	-0.035573
+10.537117	-0.026334	0.002394	9.877821	0.045832	0.087933	-0.038504
+10.538060	0.014364	-0.016758	9.839517	0.047297	0.088199	-0.038237
+10.539106	0.031123	0.002394	9.829940	0.045832	0.085534	-0.036239
+10.540140	0.023940	0.028729	9.858669	0.044766	0.085401	-0.032642
+10.541150	-0.038305	-0.016758	9.856275	0.044766	0.086334	-0.034507
+10.542088	-0.031123	-0.028729	9.827546	0.045299	0.084868	-0.034907
+10.543149	0.009576	-0.047881	9.865851	0.047297	0.084868	-0.033708
+10.544147	0.016758	-0.021546	9.849093	0.049296	0.087133	-0.037038
+10.545149	-0.002394	0.000000	9.817970	0.048096	0.090464	-0.036505
+10.546118	0.007182	0.021546	9.834729	0.047564	0.090997	-0.036772
+10.547128	0.021546	-0.014364	9.753331	0.047564	0.088865	-0.037038
+10.548075	-0.019152	-0.076609	9.770089	0.047430	0.086867	-0.037038
+10.549119	-0.031123	-0.009576	9.794030	0.046098	0.085934	-0.033708
+10.550119	0.004788	-0.004788	9.786848	0.048230	0.086734	-0.033041
+10.551148	0.014364	-0.011970	9.688692	0.049962	0.086734	-0.036639
+10.552149	0.050275	-0.009576	9.717420	0.049162	0.084868	-0.036239
+10.553154	0.071821	0.016758	9.712632	0.047430	0.086067	-0.034640
+10.554129	0.014364	0.033517	9.760513	0.046231	0.086467	-0.033841
+10.555148	0.011970	0.002394	9.806000	0.046498	0.086201	-0.033841
+10.556147	0.026334	0.026334	9.806000	0.046498	0.086600	-0.037172
+10.557149	-0.004788	0.059851	9.806000	0.047963	0.086600	-0.038904
+10.558120	0.023940	0.014364	9.772483	0.047297	0.087400	-0.037571
+10.559144	-0.038305	0.028729	9.798818	0.049828	0.087666	-0.039037
+10.560143	0.009576	-0.016758	9.896974	0.051427	0.089398	-0.037704
+10.561147	0.023940	-0.009576	9.894580	0.050228	0.087533	-0.037305
+10.562115	0.047881	-0.050275	9.875427	0.050361	0.086867	-0.033841
+10.563147	0.023940	0.011970	9.858669	0.046897	0.087400	-0.033175
+10.564149	0.014364	-0.021546	9.832334	0.045165	0.088066	-0.038904
+10.565109	0.033517	-0.067033	9.777271	0.045965	0.088998	-0.039037
+10.566150	-0.014364	-0.055063	9.762907	0.045432	0.090064	-0.036239
+10.567140	0.035911	-0.045487	9.724603	0.045165	0.086334	-0.034640
+10.568114	0.043093	-0.052669	9.777271	0.047963	0.087000	-0.036639
+10.569106	0.000000	-0.038305	9.765301	0.049695	0.090464	-0.037038
+10.570156	-0.011970	0.002394	9.784454	0.048629	0.091263	-0.039037
+10.571202	0.033517	0.009576	9.846699	0.048496	0.090997	-0.036106
+10.572198	-0.026334	0.057457	9.861063	0.047297	0.089132	-0.032242
+10.573198	0.000000	0.035911	9.827546	0.044899	0.087533	-0.034773
+10.574202	-0.016758	0.009576	9.794030	0.045165	0.085668	-0.039436
+10.575201	-0.055063	0.011970	9.774877	0.046498	0.085401	-0.040369
+10.576200	0.000000	-0.038305	9.760513	0.048896	0.087799	-0.040636
+10.577171	-0.002394	0.023940	9.839517	0.047430	0.088998	-0.035440
+10.578153	-0.002394	0.064639	9.901762	0.048363	0.088599	-0.035040
+10.579202	0.047881	0.000000	9.815576	0.048896	0.088066	-0.033974
+10.580200	0.021546	0.002394	9.782060	0.045032	0.090331	-0.034507
+10.581202	0.033517	0.028729	9.801212	0.044499	0.088466	-0.038504
+10.582203	0.064639	-0.009576	9.789242	0.046897	0.086600	-0.036239
+10.583198	0.059851	-0.014364	9.750937	0.048096	0.085401	-0.036505
+10.584200	0.069427	-0.002394	9.734179	0.048096	0.084868	-0.040103
+10.585155	0.069427	-0.043093	9.820364	0.046231	0.089531	-0.039170
+10.586141	0.064639	-0.002394	9.772483	0.044366	0.091263	-0.036106
+10.587113	0.021546	0.023940	9.750937	0.045432	0.090997	-0.036372
+10.588166	-0.035911	0.019152	9.767695	0.048096	0.088066	-0.036905
+10.589118	-0.009576	0.002394	9.772483	0.049162	0.085801	-0.037305
+10.590131	0.028729	0.021546	9.801212	0.048096	0.087000	-0.033574
+10.591202	0.028729	-0.004788	9.717420	0.045832	0.086867	-0.032109
+10.592201	-0.004788	0.000000	9.839517	0.046764	0.087000	-0.038371
+10.593140	0.021546	0.009576	9.784454	0.047430	0.088998	-0.040369
+10.594202	0.002394	0.004788	9.858669	0.047830	0.087266	-0.035173
+10.595198	0.038305	-0.076609	9.846699	0.045832	0.088599	-0.034240
+10.596200	-0.011970	-0.016758	9.784454	0.044766	0.085668	-0.033308
+10.597129	-0.057457	-0.002394	9.782060	0.048763	0.084602	-0.036639
+10.598125	-0.038305	0.021546	9.849093	0.049296	0.087933	-0.034907
+10.599138	-0.062245	0.031123	9.791636	0.047430	0.090730	-0.033441
+10.600144	-0.011970	-0.011970	9.822758	0.048896	0.090730	-0.034640
+10.601103	0.014364	0.007182	9.762907	0.049029	0.089665	-0.034773
+10.602205	0.009576	-0.031123	9.762907	0.047297	0.089931	-0.038770
+10.603201	0.002394	-0.009576	9.846699	0.046364	0.090331	-0.039303
+10.604199	0.026334	-0.031123	9.834729	0.046098	0.089931	-0.036772
+10.605201	-0.021546	-0.023940	9.779666	0.045965	0.089132	-0.037838
+10.606155	0.007182	-0.009576	9.753331	0.044366	0.088732	-0.037838
+10.607188	-0.009576	0.007182	9.834729	0.045698	0.090198	-0.034907
+10.608198	0.045487	-0.016758	9.863457	0.047963	0.090198	-0.036905
+10.609201	0.031123	-0.031123	9.839517	0.048096	0.089265	-0.039303
+10.610153	0.000000	-0.007182	9.870639	0.046231	0.088332	-0.038504
+10.611199	0.021546	-0.004788	9.784454	0.046231	0.088066	-0.037305
+10.612199	0.088580	0.000000	9.734179	0.046764	0.089665	-0.035706
+10.613199	0.040699	-0.009576	9.729391	0.045965	0.088066	-0.033841
+10.614143	0.067033	0.007182	9.822758	0.044766	0.087933	-0.037172
+10.615167	0.038305	0.011970	9.839517	0.046631	0.089931	-0.038637
+10.616157	0.021546	0.035911	9.794030	0.048363	0.092063	-0.036106
+10.617200	0.016758	-0.002394	9.715026	0.047830	0.088865	-0.034374
+10.618206	0.045487	-0.021546	9.760513	0.046364	0.087000	-0.033841
+10.619138	0.035911	0.004788	9.856275	0.046231	0.088199	-0.035440
+10.620201	0.004788	-0.011970	9.882609	0.047830	0.090597	-0.037971
+10.621200	-0.021546	-0.007182	9.868245	0.047297	0.089665	-0.036772
+10.622203	-0.023940	0.004788	9.750937	0.047164	0.089265	-0.034240
+10.623198	0.000000	-0.026334	9.794030	0.047963	0.090064	-0.037038
+10.624154	0.000000	-0.004788	9.810788	0.048896	0.090464	-0.037704
+10.625195	-0.043093	-0.004788	9.841911	0.049962	0.091130	-0.035972
+10.626204	-0.055063	0.043093	9.772483	0.050495	0.088599	-0.036905
+10.627197	0.007182	-0.069427	9.798818	0.048496	0.084602	-0.035306
+10.628197	0.004788	-0.062245	9.803606	0.047031	0.083802	-0.037971
+10.629197	0.009576	-0.038305	9.853881	0.046231	0.085934	-0.038371
+10.630138	0.055063	0.019152	9.846699	0.047031	0.087933	-0.036772
+10.631110	0.090974	-0.016758	9.801212	0.045832	0.087933	-0.033974
+10.632114	0.059851	0.004788	9.825152	0.045432	0.087666	-0.035306
+10.633141	0.019152	0.035911	9.829940	0.045565	0.089798	-0.036106
+10.634136	-0.014364	0.004788	9.796424	0.046098	0.089665	-0.036239
+10.635199	-0.062245	-0.004788	9.772483	0.043433	0.086334	-0.033574
+10.636138	0.055063	0.016758	9.786848	0.043433	0.086734	-0.035706
+10.637138	0.038305	-0.031123	9.796424	0.044899	0.087400	-0.039037
+10.638200	0.093368	0.009576	9.832334	0.046897	0.088599	-0.039570
+10.639109	0.045487	-0.004788	9.841911	0.046764	0.089931	-0.034907
+10.640128	-0.009576	-0.040699	9.806000	0.044899	0.087799	-0.032908
+10.641201	0.009576	-0.043093	9.870639	0.046897	0.084335	-0.033574
+10.642204	0.026334	-0.050275	9.896974	0.049562	0.085401	-0.035972
+10.643159	-0.004788	-0.016758	9.796424	0.047963	0.089132	-0.036772
+10.644154	0.016758	-0.023940	9.806000	0.047564	0.089398	-0.032642
+10.645196	0.069427	0.009576	9.846699	0.050361	0.089798	-0.032775
+10.646202	0.045487	-0.016758	9.829940	0.048496	0.085668	-0.033841
+10.647200	-0.035911	-0.019152	9.817970	0.044632	0.085002	-0.034907
+10.648199	0.016758	-0.004788	9.760513	0.045299	0.086201	-0.034107
+10.649195	0.000000	-0.009576	9.801212	0.045565	0.086734	-0.036505
+10.650202	0.009576	0.045487	9.796424	0.046764	0.089265	-0.038504
+10.651137	-0.028729	0.028729	9.832334	0.048363	0.088199	-0.036772
+10.652152	0.009576	-0.043093	9.813182	0.048363	0.088466	-0.033841
+10.653155	-0.011970	-0.023940	9.825152	0.046364	0.088599	-0.034907
+10.654197	0.000000	-0.043093	9.772483	0.045432	0.086067	-0.038504
+10.655199	0.021546	-0.035911	9.791636	0.046631	0.087000	-0.039037
+10.656199	0.009576	0.007182	9.825152	0.047830	0.087400	-0.037838
+10.657204	-0.014364	0.011970	9.827546	0.047430	0.085401	-0.036505
+10.658205	0.016758	-0.023940	9.760513	0.048230	0.087933	-0.034240
+10.659199	0.038305	-0.004788	9.815576	0.049562	0.092063	-0.037172
+10.660145	-0.009576	0.011970	9.877821	0.047564	0.090730	-0.036372
+10.661140	0.047881	-0.045487	9.844305	0.047297	0.087133	-0.035306
+10.662153	0.050275	-0.040699	9.844305	0.045698	0.086067	-0.035972
+10.663193	0.026334	0.035911	9.808394	0.046364	0.087666	-0.034507
+10.664139	-0.007182	0.079003	9.839517	0.046498	0.089665	-0.036372
+10.665143	0.035911	-0.023940	9.755725	0.046498	0.085668	-0.037038
+10.666202	0.071821	-0.064639	9.772483	0.047963	0.086734	-0.036239
+10.667199	0.021546	-0.083792	9.870639	0.049962	0.090064	-0.038637
+10.668152	0.009576	0.031123	9.853881	0.047830	0.090331	-0.035839
+10.669134	-0.007182	0.045487	9.794030	0.045432	0.090597	-0.034374
+10.670129	0.004788	0.043093	9.803606	0.046231	0.090864	-0.032375
+10.671133	0.076609	0.007182	9.772483	0.045432	0.089531	-0.035040
+10.672153	0.050275	0.004788	9.779666	0.045698	0.085002	-0.032375
+10.673195	-0.031123	-0.028729	9.825152	0.047164	0.083802	-0.034107
+10.674203	0.069427	-0.028729	9.765301	0.047564	0.085135	-0.033708
+10.675198	0.016758	0.035911	9.765301	0.044366	0.085801	-0.033841
+10.676199	0.033517	0.014364	9.782060	0.043300	0.086734	-0.038371
+10.677200	0.028729	0.007182	9.772483	0.045165	0.087666	-0.042234
+10.678162	0.016758	0.047881	9.782060	0.047430	0.087933	-0.035972
+10.679137	-0.004788	0.050275	9.798818	0.046231	0.088066	-0.031309
+10.680196	0.009576	-0.021546	9.808394	0.046231	0.087799	-0.035173
+10.681158	0.007182	-0.014364	9.806000	0.046631	0.086734	-0.038637
+10.682194	0.040699	0.007182	9.841911	0.047164	0.086334	-0.036772
+10.683199	0.055063	-0.033517	9.738967	0.045832	0.090597	-0.034907
+10.684196	0.011970	-0.043093	9.743755	0.045432	0.091397	-0.033308
+10.685138	-0.002394	-0.023940	9.779666	0.046897	0.090064	-0.035040
+10.686202	-0.033517	-0.014364	9.770089	0.048096	0.085801	-0.035972
+10.687196	0.028729	0.014364	9.822758	0.046364	0.086334	-0.037038
+10.688197	0.033517	-0.009576	9.710238	0.045698	0.089665	-0.035440
+10.689095	0.100550	0.009576	9.753331	0.045965	0.089798	-0.036239
+10.690131	0.057457	-0.050275	9.813182	0.046231	0.088066	-0.035040
+10.691147	-0.014364	-0.031123	9.913732	0.045832	0.087799	-0.034507
+10.692173	0.023940	0.014364	9.901762	0.049162	0.088998	-0.037838
+10.693103	-0.050275	-0.028729	9.746149	0.049695	0.088599	-0.040369
+10.694111	0.023940	-0.023940	9.765301	0.048763	0.087666	-0.038504
+10.695095	-0.014364	0.028729	9.863457	0.048763	0.087799	-0.037305
+10.696095	-0.004788	-0.009576	9.837123	0.049429	0.087666	-0.034773
+10.697133	0.007182	-0.009576	9.870639	0.046098	0.089665	-0.035306
+10.698135	-0.043093	-0.031123	9.849093	0.045698	0.087533	-0.034907
+10.699215	0.035911	-0.009576	9.837123	0.048363	0.086334	-0.035040
+10.700108	0.019152	0.028729	9.827546	0.047297	0.086334	-0.038770
+10.701128	0.014364	0.016758	9.832334	0.048629	0.087000	-0.039703
+10.702137	0.050275	-0.045487	9.829940	0.048896	0.088599	-0.036505
+10.703133	-0.016758	-0.045487	9.810788	0.046897	0.087000	-0.035706
+10.704137	0.016758	-0.011970	9.782060	0.045698	0.085534	-0.035173
+10.705201	0.043093	-0.011970	9.873033	0.045832	0.087000	-0.032642
+10.706201	0.040699	0.043093	9.851487	0.047031	0.086600	-0.033708
+10.707199	-0.007182	0.007182	9.784454	0.046631	0.089398	-0.038104
+10.708142	-0.002394	0.007182	9.750937	0.043833	0.089531	-0.040769
+10.709158	-0.002394	0.021546	9.760513	0.043700	0.087266	-0.037704
+10.710140	-0.007182	-0.023940	9.820364	0.046764	0.086734	-0.034907
+10.711134	-0.038305	-0.040699	9.767695	0.046897	0.089931	-0.033974
+10.712157	-0.021546	-0.023940	9.784454	0.047297	0.091663	-0.030776
+10.713140	-0.019152	-0.031123	9.815576	0.049162	0.090864	-0.035040
+10.714119	-0.031123	0.009576	9.806000	0.049562	0.087666	-0.038371
+10.715136	-0.002394	0.007182	9.789242	0.047830	0.086201	-0.037305
+10.716142	-0.004788	0.021546	9.767695	0.046897	0.087000	-0.037438
+10.717200	-0.019152	0.014364	9.798818	0.047297	0.087000	-0.034507
+10.718161	-0.016758	-0.009576	9.853881	0.047031	0.088466	-0.034907
+10.719198	0.023940	-0.062245	9.877821	0.047830	0.087933	-0.035839
+10.720202	0.038305	-0.074215	9.928096	0.047963	0.090730	-0.039170
+10.721198	0.019152	-0.016758	9.875427	0.047430	0.087799	-0.038504
+10.722199	0.004788	-0.040699	9.770089	0.047697	0.088732	-0.036772
+10.723132	0.074215	0.016758	9.822758	0.046364	0.089398	-0.035972
+10.724153	0.019152	-0.016758	9.817970	0.044499	0.088732	-0.040769
+10.725137	0.026334	0.000000	9.899368	0.045299	0.087400	-0.039303
+10.726113	-0.040699	-0.021546	9.803606	0.048763	0.086201	-0.035573
+10.727136	-0.014364	0.004788	9.825152	0.047430	0.086067	-0.037571
+10.728134	-0.021546	-0.002394	9.837123	0.046631	0.088865	-0.036639
+10.729193	-0.026334	-0.021546	9.863457	0.048496	0.088998	-0.035173
+10.730135	0.011970	-0.016758	9.873033	0.048763	0.087133	-0.033441
+10.731198	0.019152	0.004788	9.815576	0.049828	0.082737	-0.033708
+10.732198	0.009576	0.000000	9.784454	0.047031	0.083403	-0.034107
+10.733135	0.019152	-0.031123	9.813182	0.044100	0.086201	-0.039436
+10.734161	0.011970	-0.021546	9.784454	0.044100	0.088466	-0.035573
+10.735129	0.009576	-0.076609	9.791636	0.045832	0.088865	-0.034773
+10.736135	0.007182	-0.043093	9.796424	0.047697	0.089798	-0.036772
+10.737114	-0.016758	-0.052669	9.765301	0.046231	0.090464	-0.035440
+10.738140	0.007182	-0.045487	9.796424	0.046498	0.088865	-0.037172
+10.739125	-0.004788	-0.007182	9.858669	0.045965	0.084868	-0.040236
+10.740106	0.033517	-0.047881	9.801212	0.047164	0.084335	-0.036372
+10.741105	0.026334	-0.038305	9.726997	0.046364	0.087933	-0.035573
+10.742110	0.014364	-0.031123	9.717420	0.044766	0.088865	-0.039703
+10.743106	0.007182	-0.069427	9.746149	0.045565	0.088199	-0.037038
+10.744133	0.040699	-0.074215	9.803606	0.046897	0.088466	-0.036239
+10.745128	0.043093	0.014364	9.839517	0.048896	0.088466	-0.035306
+10.746208	0.031123	-0.004788	9.717420	0.047564	0.089798	-0.034107
+10.747133	0.090974	-0.016758	9.762907	0.046764	0.087799	-0.038770
+10.748144	0.043093	-0.011970	9.834729	0.047031	0.087666	-0.038237
+10.749135	0.009576	-0.062245	9.906550	0.047430	0.088066	-0.038104
+10.750125	0.047881	-0.050275	9.856275	0.047564	0.089531	-0.036905
+10.751133	0.038305	0.002394	9.853881	0.049695	0.090997	-0.036239
+10.752106	0.031123	-0.014364	9.834729	0.049029	0.090730	-0.036905
+10.753199	0.007182	-0.016758	9.901762	0.047830	0.089132	-0.036106
+10.754203	0.040699	0.000000	9.817970	0.047164	0.087266	-0.032775
+10.755196	0.038305	0.033517	9.791636	0.045698	0.085534	-0.034640
+10.756153	0.040699	0.011970	9.853881	0.046231	0.087400	-0.034907
+10.757130	0.035911	-0.011970	9.817970	0.046764	0.090198	-0.033308
+10.758200	0.040699	0.016758	9.858669	0.045299	0.088865	-0.032775
+10.759199	-0.031123	0.093368	9.839517	0.044766	0.087933	-0.038904
+10.760199	0.004788	0.031123	9.796424	0.046231	0.088998	-0.039570
+10.761199	-0.040699	0.000000	9.837123	0.050228	0.089398	-0.036239
+10.762202	0.028729	0.014364	9.832334	0.050628	0.087000	-0.034640
+10.763201	-0.014364	-0.021546	9.846699	0.048230	0.087266	-0.031975
+10.764198	0.050275	-0.045487	9.817970	0.046897	0.089531	-0.034374
+10.765138	0.033517	-0.007182	9.784454	0.049296	0.091663	-0.034374
+10.766156	0.000000	0.011970	9.832334	0.051161	0.088732	-0.039570
+10.767198	0.011970	-0.023940	9.710238	0.049962	0.087266	-0.041302
+10.768120	0.007182	-0.028729	9.782060	0.047697	0.088066	-0.036106
+10.769140	-0.035911	-0.023940	9.806000	0.046498	0.088599	-0.033708
+10.770135	0.028729	-0.038305	9.798818	0.047031	0.089931	-0.036639
+10.771199	0.045487	-0.004788	9.796424	0.047430	0.087933	-0.035306
+10.772199	0.035911	-0.028729	9.758119	0.046764	0.086334	-0.036772
+10.773198	-0.035911	0.004788	9.829940	0.046897	0.088865	-0.037838
+10.774153	0.023940	-0.019152	9.829940	0.047164	0.087933	-0.034507
+10.775192	0.026334	0.014364	9.810788	0.048629	0.082737	-0.034507
+10.776203	0.021546	-0.009576	9.822758	0.048496	0.084335	-0.034507
+10.777201	0.028729	-0.031123	9.825152	0.046364	0.087266	-0.037571
+10.778204	-0.014364	-0.059851	9.889792	0.044766	0.087400	-0.036372
+10.779200	0.009576	-0.014364	9.806000	0.047830	0.087933	-0.036772
+10.780133	0.040699	0.021546	9.770089	0.050095	0.088732	-0.035040
+10.781196	0.021546	0.021546	9.774877	0.047830	0.089531	-0.035040
+10.782201	0.004788	-0.002394	9.808394	0.044233	0.089265	-0.036905
+10.783155	-0.007182	-0.007182	9.870639	0.045165	0.091397	-0.034640
+10.784196	0.026334	-0.014364	9.810788	0.047963	0.088599	-0.037704
+10.785204	0.007182	-0.043093	9.794030	0.048763	0.086201	-0.036772
+10.786203	0.002394	-0.014364	9.767695	0.048629	0.087400	-0.032908
+10.787198	-0.021546	0.002394	9.782060	0.047164	0.084202	-0.033574
+10.788198	-0.002394	-0.011970	9.729391	0.047297	0.083802	-0.035173
+10.789137	0.067033	0.045487	9.765301	0.045432	0.088732	-0.037438
+10.790129	-0.016758	-0.009576	9.796424	0.047697	0.090597	-0.037971
+10.791202	-0.019152	-0.004788	9.817970	0.050095	0.089665	-0.036106
+10.792153	-0.035911	-0.033517	9.913732	0.047430	0.089398	-0.035040
+10.793195	0.000000	-0.045487	9.882609	0.044766	0.088599	-0.037305
+10.794169	0.009576	0.009576	9.844305	0.045832	0.088998	-0.036505
+10.795126	0.038305	0.019152	9.758119	0.047031	0.090730	-0.035706
+10.796200	0.007182	0.011970	9.782060	0.045432	0.087933	-0.035173
+10.797199	0.035911	-0.002394	9.774877	0.043833	0.087133	-0.039969
+10.798202	-0.007182	0.028729	9.853881	0.045565	0.087799	-0.039303
+10.799128	0.002394	-0.004788	9.817970	0.047164	0.086201	-0.037172
+10.800115	0.004788	-0.014364	9.822758	0.047697	0.086201	-0.038237
+10.801155	-0.031123	0.023940	9.829940	0.047430	0.086467	-0.036639
+10.802140	0.019152	0.002394	9.813182	0.046098	0.085801	-0.035173
+10.803200	-0.028729	0.000000	9.796424	0.045432	0.085534	-0.036639
+10.804198	0.019152	-0.045487	9.837123	0.048629	0.089132	-0.038904
+10.805198	0.000000	-0.069427	9.791636	0.050761	0.091397	-0.037172
+10.806203	0.052669	0.000000	9.791636	0.046631	0.088998	-0.035573
+10.807152	0.067033	-0.002394	9.777271	0.045698	0.087400	-0.039170
+10.808198	-0.028729	-0.043093	9.820364	0.047830	0.087666	-0.038504
+10.809159	-0.043093	-0.033517	9.746149	0.042368	0.088466	-0.037838
+10.810160	0.007182	-0.035911	9.810788	0.043167	0.090730	-0.038237
+10.811136	0.043093	-0.074215	9.748543	0.048363	0.090997	-0.037971
+10.812197	0.023940	-0.007182	9.827546	0.050761	0.088066	-0.036106
+10.813137	0.023940	0.011970	9.870639	0.051028	0.087000	-0.034107
+10.814135	0.019152	-0.016758	9.892186	0.046098	0.087000	-0.035040
+10.815123	-0.011970	0.009576	9.837123	0.043167	0.089132	-0.037038
+10.816127	-0.033517	-0.009576	9.760513	0.046098	0.089265	-0.035706
+10.817127	-0.031123	-0.040699	9.858669	0.048363	0.090198	-0.033974
+10.818126	0.016758	-0.047881	9.849093	0.049562	0.091930	-0.037571
+10.819132	-0.021546	-0.023940	9.803606	0.047564	0.089931	-0.037971
+10.820129	-0.007182	-0.007182	9.858669	0.045032	0.088466	-0.037704
+10.821162	0.009576	-0.033517	9.779666	0.044499	0.089531	-0.034907
+10.822200	-0.002394	0.002394	9.724603	0.045432	0.087933	-0.033308
+10.823199	-0.031123	-0.009576	9.810788	0.047963	0.085268	-0.035173
+10.824198	0.028729	-0.019152	9.837123	0.050495	0.087133	-0.036505
+10.825199	0.026334	0.002394	9.767695	0.050628	0.088466	-0.037438
+10.826200	-0.007182	0.031123	9.806000	0.047164	0.089265	-0.037038
+10.827199	-0.023940	0.014364	9.791636	0.044366	0.090864	-0.035972
+10.828198	0.019152	0.047881	9.779666	0.045032	0.087400	-0.035440
+10.829153	0.007182	-0.011970	9.837123	0.048096	0.085534	-0.039570
+10.830153	0.011970	-0.045487	9.894580	0.049562	0.088732	-0.038371
+10.831197	-0.028729	-0.038305	9.794030	0.047564	0.089531	-0.038237
+10.832198	-0.052669	-0.067033	9.806000	0.047031	0.087933	-0.035173
+10.833199	-0.040699	-0.033517	9.750937	0.049162	0.088199	-0.033308
+10.834202	0.016758	-0.050275	9.777271	0.050095	0.089132	-0.034507
+10.835129	0.045487	0.000000	9.832334	0.048496	0.089132	-0.034773
+10.836156	0.019152	-0.009576	9.865851	0.045832	0.087933	-0.036505
+10.837173	0.000000	-0.004788	9.810788	0.048763	0.088199	-0.037971
+10.838154	0.007182	0.007182	9.779666	0.049828	0.087400	-0.036639
+10.839151	0.047881	0.009576	9.849093	0.049162	0.085801	-0.034640
+10.840106	-0.019152	0.038305	9.885003	0.047963	0.084069	-0.038104
+10.841200	-0.002394	0.014364	9.786848	0.049162	0.086334	-0.039170
+10.842201	-0.040699	-0.057457	9.789242	0.048496	0.087400	-0.038237
+10.843198	-0.035911	-0.031123	9.825152	0.046897	0.089531	-0.038104
+10.844150	-0.071821	0.004788	9.798818	0.045165	0.090064	-0.036505
+10.845135	0.004788	0.023940	9.760513	0.045698	0.089665	-0.036905
+10.846152	0.040699	0.057457	9.698268	0.048629	0.086467	-0.038104
+10.847175	-0.040699	0.014364	9.772483	0.047963	0.087933	-0.038504
+10.848199	-0.028729	0.064639	9.846699	0.046231	0.088066	-0.039836
+10.849161	-0.031123	0.023940	9.894580	0.045965	0.089265	-0.037038
+10.850136	-0.004788	0.004788	9.767695	0.048230	0.086867	-0.033974
+10.851130	0.016758	0.028729	9.786848	0.047031	0.087000	-0.038237
+10.852118	0.004788	-0.016758	9.877821	0.043700	0.088732	-0.038770
+10.853197	-0.007182	-0.011970	9.877821	0.043567	0.089132	-0.039570
+10.854200	-0.011970	-0.045487	9.765301	0.046498	0.086734	-0.037971
+10.855148	-0.007182	0.004788	9.803606	0.048496	0.086467	-0.032508
+10.856193	0.019152	-0.007182	9.827546	0.046631	0.088066	-0.036106
+10.857197	0.052669	0.028729	9.786848	0.046897	0.089798	-0.038504
+10.858202	0.011970	0.031123	9.794030	0.043966	0.089132	-0.038504
+10.859137	-0.040699	-0.009576	9.777271	0.044499	0.090597	-0.038637
+10.860141	-0.002394	0.019152	9.794030	0.047963	0.090198	-0.038104
+10.861119	0.014364	0.043093	9.803606	0.050095	0.086201	-0.037172
+10.862113	0.028729	0.031123	9.741361	0.049429	0.087133	-0.036639
+10.863117	-0.007182	-0.023940	9.770089	0.045698	0.084868	-0.038504
+10.864129	-0.019152	0.016758	9.832334	0.043034	0.087400	-0.038104
+10.865132	0.007182	0.014364	9.813182	0.044632	0.087933	-0.037038
+10.866200	0.000000	-0.014364	9.825152	0.047830	0.085534	-0.035706
+10.867147	0.019152	-0.009576	9.817970	0.047830	0.088066	-0.037305
+10.868112	0.067033	-0.011970	9.796424	0.047031	0.087533	-0.036772
+10.869120	0.035911	0.002394	9.703056	0.045432	0.088332	-0.036905
+10.870125	0.028729	0.028729	9.695874	0.048230	0.087133	-0.036905
+10.871123	0.052669	-0.004788	9.810788	0.049562	0.086334	-0.036639
+10.872123	0.040699	0.023940	9.820364	0.046897	0.083936	-0.034640
+10.873124	-0.038305	0.045487	9.758119	0.046098	0.084602	-0.034640
+10.874056	-0.019152	0.007182	9.817970	0.046231	0.088466	-0.034107
+10.875057	0.016758	-0.035911	9.877821	0.046764	0.090064	-0.034773
+10.876061	0.011970	-0.035911	9.873033	0.048230	0.088998	-0.038104
+10.877060	0.009576	0.023940	9.815576	0.047164	0.085268	-0.033841
+10.878077	-0.035911	0.038305	9.796424	0.046631	0.084202	-0.037038
+10.879060	-0.057457	0.052669	9.801212	0.049162	0.085401	-0.038770
+10.880135	-0.016758	0.002394	9.803606	0.047297	0.085934	-0.038104
+10.881137	0.007182	0.002394	9.772483	0.046764	0.087666	-0.038237
+10.882139	0.035911	0.023940	9.801212	0.049296	0.090864	-0.038904
+10.883135	0.014364	0.002394	9.870639	0.049695	0.091663	-0.038104
+10.884094	-0.004788	0.021546	9.817970	0.046897	0.089798	-0.037704
+10.885067	0.038305	-0.043093	9.784454	0.046098	0.086867	-0.037571
+10.886036	0.028729	0.000000	9.782060	0.046631	0.086201	-0.035839
+10.887047	0.007182	0.019152	9.817970	0.047697	0.086734	-0.038770
+10.888056	-0.002394	-0.016758	9.853881	0.047164	0.086600	-0.036639
+10.889057	0.026334	-0.028729	9.801212	0.048496	0.087133	-0.035573
+10.890058	-0.028729	-0.045487	9.791636	0.048896	0.086067	-0.034907
+10.891133	0.011970	-0.028729	9.834729	0.047164	0.086201	-0.035706
+10.892138	0.014364	-0.026334	9.825152	0.046764	0.086600	-0.040769
+10.893084	0.016758	0.055063	9.815576	0.046631	0.086734	-0.040369
+10.894137	-0.028729	0.031123	9.841911	0.048363	0.087666	-0.035040
+10.895131	0.004788	-0.071821	9.877821	0.048629	0.087799	-0.033441
+10.896057	0.055063	-0.033517	9.829940	0.046631	0.087666	-0.033175
+10.897079	0.026334	-0.009576	9.832334	0.048096	0.089931	-0.041568
+10.898136	-0.019152	-0.002394	9.760513	0.051161	0.090597	-0.042501
+10.899123	-0.007182	-0.035911	9.815576	0.048096	0.088466	-0.037305
+10.900066	0.026334	-0.026334	9.803606	0.045565	0.087799	-0.034907
+10.901071	-0.021546	0.019152	9.755725	0.044766	0.085135	-0.036239
+10.902049	0.000000	0.071821	9.782060	0.044766	0.088066	-0.037172
+10.903075	0.031123	0.014364	9.806000	0.044766	0.088599	-0.035040
+10.904086	-0.028729	-0.004788	9.801212	0.045432	0.086334	-0.033974
+10.905087	-0.062245	0.043093	9.798818	0.048230	0.082737	-0.035706
+10.906087	-0.043093	0.028729	9.791636	0.048230	0.086201	-0.039170
+10.907087	0.007182	-0.009576	9.712632	0.046098	0.090331	-0.041035
+10.908087	0.047881	-0.004788	9.698268	0.049562	0.091530	-0.037438
+10.909088	0.040699	-0.026334	9.796424	0.048763	0.090597	-0.037838
+10.910091	0.011970	-0.026334	9.762907	0.048230	0.086467	-0.037038
+10.911073	0.004788	-0.016758	9.736573	0.046764	0.087400	-0.039969
+10.912087	0.021546	0.002394	9.774877	0.045032	0.087000	-0.037438
+10.913087	0.011970	0.062245	9.911338	0.046231	0.087266	-0.037172
+10.914086	-0.011970	0.028729	9.861063	0.045832	0.088599	-0.034640
+10.915086	-0.021546	0.019152	9.803606	0.045698	0.088332	-0.033441
+10.916089	-0.007182	0.002394	9.839517	0.046764	0.088599	-0.033441
+10.917059	-0.021546	-0.004788	9.839517	0.046764	0.088199	-0.036106
+10.918053	0.019152	0.064639	9.796424	0.047564	0.087400	-0.037838
+10.919066	0.035911	0.021546	9.810788	0.046364	0.088332	-0.037971
+10.920107	0.055063	0.023940	9.803606	0.047697	0.085668	-0.034773
+10.921136	-0.004788	0.069427	9.822758	0.048363	0.086201	-0.032508
+10.922137	0.009576	0.031123	9.777271	0.045565	0.087400	-0.032908
+10.923136	0.043093	0.004788	9.762907	0.044499	0.086734	-0.035839
+10.924135	0.067033	-0.004788	9.779666	0.046631	0.088599	-0.039570
+10.925103	0.043093	-0.014364	9.772483	0.047297	0.087933	-0.034640
+10.926125	-0.023940	-0.016758	9.808394	0.048363	0.086201	-0.033041
+10.927139	-0.014364	-0.004788	9.765301	0.048629	0.088599	-0.033574
+10.928137	0.040699	0.007182	9.846699	0.045032	0.087666	-0.037038
+10.929067	0.052669	-0.007182	9.698268	0.047430	0.087799	-0.040636
+10.930138	-0.009576	0.031123	9.738967	0.049962	0.089665	-0.039969
+10.931130	0.047881	-0.023940	9.829940	0.048230	0.088865	-0.038770
+10.932135	0.014364	-0.033517	9.837123	0.047297	0.088199	-0.035972
+10.933135	-0.021546	-0.047881	9.789242	0.048096	0.089265	-0.035173
+10.934136	-0.007182	0.011970	9.760513	0.047830	0.087799	-0.036905
+10.935116	0.043093	0.011970	9.820364	0.048363	0.086467	-0.040902
+10.936148	0.045487	-0.004788	9.861063	0.047164	0.086201	-0.041435
+10.937139	0.009576	-0.011970	9.901762	0.047297	0.084069	-0.035972
+10.938137	0.021546	0.011970	9.825152	0.046498	0.086201	-0.034107
+10.939134	0.028729	0.064639	9.837123	0.046764	0.087400	-0.037704
+10.940137	0.026334	-0.009576	9.813182	0.047031	0.086734	-0.039436
+10.941135	-0.002394	-0.031123	9.827546	0.046631	0.086201	-0.036639
+10.942136	0.016758	-0.023940	9.777271	0.048363	0.086067	-0.040769
+10.943093	0.009576	-0.014364	9.774877	0.047297	0.085268	-0.039836
+10.944121	0.035911	-0.067033	9.822758	0.046897	0.086467	-0.036106
+10.945095	0.035911	-0.009576	9.889792	0.043833	0.086867	-0.034240
+10.946099	-0.033517	-0.002394	9.849093	0.044233	0.087133	-0.036106
+10.947086	-0.028729	-0.016758	9.841911	0.046364	0.087266	-0.036239
+10.948088	-0.004788	0.045487	9.815576	0.047697	0.088732	-0.035306
+10.949085	-0.067033	0.021546	9.870639	0.046364	0.090331	-0.036639
+10.950091	-0.040699	-0.023940	9.861063	0.045032	0.090997	-0.039170
+10.951133	0.028729	0.031123	9.832334	0.045299	0.088998	-0.040502
+10.952119	0.004788	0.052669	9.827546	0.047697	0.086334	-0.039303
+10.953137	0.028729	0.031123	9.863457	0.047031	0.090064	-0.036905
+10.954140	-0.007182	0.043093	9.779666	0.045698	0.092196	-0.035706
+10.955134	-0.040699	0.021546	9.798818	0.045032	0.089531	-0.032642
+10.956118	-0.011970	-0.033517	9.806000	0.044499	0.086467	-0.034374
+10.957147	0.028729	0.021546	9.772483	0.045032	0.085801	-0.035839
+10.958136	-0.009576	0.004788	9.870639	0.046364	0.088332	-0.039170
+10.959138	-0.071821	-0.023940	9.779666	0.044100	0.087799	-0.039703
+10.960077	-0.014364	-0.035911	9.741361	0.043700	0.085934	-0.036639
+10.961134	-0.004788	0.007182	9.748543	0.044499	0.086867	-0.035306
+10.962138	-0.007182	0.026334	9.765301	0.046231	0.086467	-0.037704
+10.963134	0.021546	-0.021546	9.777271	0.046364	0.085801	-0.039170
+10.964137	0.081397	0.000000	9.676722	0.045832	0.089132	-0.038637
+10.965068	-0.004788	-0.040699	9.810788	0.046498	0.091130	-0.036239
+10.966137	0.019152	-0.019152	9.810788	0.047297	0.087133	-0.033974
+10.967136	0.023940	-0.007182	9.839517	0.047830	0.082337	-0.031043
+10.968120	0.002394	-0.038305	9.772483	0.047830	0.083270	-0.034907
+10.969135	-0.007182	-0.007182	9.772483	0.047564	0.087266	-0.035040
+10.970137	0.067033	0.021546	9.853881	0.047031	0.089931	-0.033574
+10.971134	0.052669	-0.023940	9.849093	0.046897	0.090198	-0.034773
+10.972137	0.031123	-0.040699	9.837123	0.048096	0.088199	-0.034107
+10.973135	-0.023940	-0.067033	9.786848	0.047430	0.085801	-0.038904
+10.974139	0.011970	-0.035911	9.750937	0.045432	0.087799	-0.041035
+10.975129	-0.011970	-0.004788	9.801212	0.044233	0.088998	-0.038104
+10.976134	0.050275	0.026334	9.863457	0.044899	0.089132	-0.035972
+10.977136	0.002394	-0.014364	9.726997	0.046364	0.087666	-0.039436
+10.978108	-0.014364	-0.040699	9.712632	0.045832	0.087666	-0.037438
+10.979137	-0.004788	-0.026334	9.755725	0.046231	0.083936	-0.036505
+10.980134	-0.021546	0.014364	9.772483	0.046498	0.085801	-0.035440
+10.981136	-0.004788	0.038305	9.841911	0.045832	0.088332	-0.035306
+10.982138	0.035911	0.014364	9.815576	0.046364	0.087933	-0.034374
+10.983129	0.026334	-0.021546	9.765301	0.048363	0.088466	-0.033841
+10.984134	0.033517	-0.016758	9.774877	0.047963	0.086467	-0.032375
+10.985068	-0.007182	-0.028729	9.832334	0.047430	0.087400	-0.032908
+10.986136	-0.021546	-0.040699	9.822758	0.047297	0.088732	-0.036505
+10.987121	0.014364	-0.055063	9.801212	0.047164	0.088599	-0.035440
+10.988128	0.019152	-0.047881	9.858669	0.048363	0.087799	-0.034640
+10.989135	0.007182	-0.011970	9.741361	0.046764	0.088865	-0.035173
+10.990096	-0.033517	0.021546	9.834729	0.047564	0.090198	-0.035573
+10.991137	-0.016758	0.026334	9.887397	0.045698	0.090864	-0.034507
+10.992135	-0.045487	0.011970	9.839517	0.045032	0.086600	-0.037172
+10.993132	0.009576	-0.045487	9.779666	0.047430	0.084602	-0.035306
+10.994137	-0.033517	-0.028729	9.772483	0.048230	0.086067	-0.033308
+10.995136	-0.038305	-0.009576	9.779666	0.047963	0.087666	-0.036239
+10.996070	0.004788	-0.011970	9.827546	0.048496	0.087799	-0.037172
+10.997112	0.004788	0.023940	9.808394	0.047830	0.086734	-0.036239
+10.998128	-0.021546	0.033517	9.724603	0.046364	0.088998	-0.034640
+10.999074	-0.014364	0.050275	9.750937	0.047031	0.087133	-0.034907
+11.000129	0.014364	0.071821	9.736573	0.046764	0.086467	-0.036505
+11.001136	-0.031123	0.014364	9.693480	0.045165	0.086734	-0.035839
+11.002137	0.004788	-0.019152	9.748543	0.045165	0.087933	-0.035839
+11.003135	0.038305	0.004788	9.796424	0.046764	0.088732	-0.035839
+11.004136	-0.021546	0.023940	9.736573	0.047697	0.087400	-0.036772
+11.005129	0.004788	0.050275	9.779666	0.047297	0.087000	-0.036372
+11.006136	0.050275	0.055063	9.794030	0.047697	0.087933	-0.035440
+11.007136	0.014364	-0.002394	9.870639	0.047164	0.087933	-0.032375
+11.008116	-0.035911	-0.033517	9.784454	0.048096	0.087666	-0.038371
+11.009133	0.011970	-0.019152	9.722208	0.048363	0.086334	-0.039836
+11.010068	0.021546	-0.002394	9.832334	0.047830	0.088732	-0.041568
+11.011136	0.000000	-0.007182	9.813182	0.047164	0.089398	-0.040769
+11.012137	-0.014364	-0.023940	9.834729	0.044899	0.086467	-0.035440
+11.013134	0.045487	-0.045487	9.755725	0.045032	0.087799	-0.035040
+11.014094	0.007182	-0.043093	9.762907	0.046231	0.090064	-0.036106
+11.015129	0.033517	0.002394	9.779666	0.047963	0.088332	-0.038637
+11.016133	-0.002394	0.052669	9.882609	0.047963	0.085801	-0.041168
+11.017136	0.002394	0.038305	9.851487	0.047564	0.086867	-0.037704
+11.018124	0.016758	0.004788	9.873033	0.048763	0.085668	-0.035706
+11.019138	0.038305	-0.016758	9.827546	0.049962	0.087000	-0.034640
+11.020135	0.009576	0.000000	9.839517	0.048763	0.088732	-0.030377
+11.021136	0.011970	-0.028729	9.856275	0.046098	0.089665	-0.032908
+11.022137	0.026334	-0.016758	9.817970	0.043034	0.090464	-0.037038
+11.023136	-0.045487	0.004788	9.798818	0.045299	0.088865	-0.040636
+11.024136	-0.016758	-0.062245	9.791636	0.047164	0.088199	-0.041435
+11.025135	-0.047881	-0.055063	9.741361	0.047830	0.087000	-0.038770
+11.026137	0.031123	0.014364	9.786848	0.047164	0.086734	-0.036639
+11.027116	0.002394	0.064639	9.849093	0.048896	0.087533	-0.037172
+11.028100	-0.014364	0.040699	9.841911	0.050095	0.087933	-0.036106
+11.029158	-0.007182	0.026334	9.798818	0.047297	0.088466	-0.035440
+11.030118	-0.019152	-0.038305	9.829940	0.045965	0.088466	-0.039969
+11.031136	-0.047881	-0.007182	9.762907	0.045299	0.087933	-0.038371
+11.032131	-0.019152	-0.028729	9.789242	0.044766	0.088466	-0.036106
+11.033137	0.004788	0.002394	9.846699	0.048096	0.089665	-0.037971
+11.034137	0.009576	0.026334	9.858669	0.049162	0.089531	-0.034374
+11.035129	-0.009576	-0.019152	9.853881	0.045965	0.085534	-0.037438
+11.036133	-0.021546	-0.026334	9.784454	0.047564	0.086201	-0.036239
+11.037137	-0.004788	-0.047881	9.765301	0.048629	0.085801	-0.033974
+11.038107	0.019152	-0.031123	9.770089	0.045698	0.086067	-0.034640
+11.039112	-0.009576	-0.069427	9.794030	0.045832	0.085002	-0.032775
+11.040081	-0.009576	-0.023940	9.822758	0.047031	0.084202	-0.034773
+11.041136	0.000000	-0.043093	9.825152	0.048096	0.086467	-0.035440
+11.042137	0.035911	-0.028729	9.822758	0.047031	0.089798	-0.036905
+11.043132	0.062245	0.021546	9.846699	0.046364	0.087933	-0.034773
+11.044133	-0.009576	0.004788	9.786848	0.047297	0.087666	-0.039170
+11.045115	-0.019152	-0.016758	9.736573	0.045832	0.087666	-0.036772
+11.046077	0.007182	-0.033517	9.762907	0.045165	0.085934	-0.036239
+11.047123	0.000000	-0.004788	9.760513	0.044499	0.087799	-0.037305
+11.048139	0.004788	-0.014364	9.760513	0.046098	0.087133	-0.036772
+11.049079	0.009576	-0.002394	9.810788	0.049296	0.087400	-0.036372
+11.050065	0.014364	-0.052669	9.762907	0.048363	0.087933	-0.035706
+11.051146	-0.011970	-0.033517	9.789242	0.046364	0.087533	-0.036239
+11.052135	-0.057457	-0.040699	9.827546	0.046631	0.087666	-0.037038
+11.053135	-0.033517	-0.007182	9.760513	0.046364	0.087666	-0.037571
+11.054133	0.000000	-0.019152	9.803606	0.045032	0.088865	-0.037305
+11.055135	-0.035911	-0.045487	9.829940	0.046764	0.088199	-0.033708
+11.056136	0.000000	-0.031123	9.760513	0.046631	0.087266	-0.033974
+11.057130	-0.031123	-0.007182	9.825152	0.045965	0.088599	-0.033574
+11.058133	-0.031123	-0.033517	9.861063	0.043034	0.090331	-0.039436
+11.059126	-0.064639	-0.043093	9.844305	0.042900	0.088066	-0.039703
+11.060067	-0.014364	0.016758	9.786848	0.047297	0.085534	-0.037704
+11.061068	0.011970	-0.047881	9.822758	0.045565	0.085135	-0.035706
+11.062136	0.021546	-0.009576	9.889792	0.047297	0.086867	-0.036772
+11.063132	0.004788	-0.002394	9.817970	0.047297	0.086067	-0.037571
+11.064133	0.047881	0.000000	9.798818	0.047564	0.088466	-0.036505
+11.065138	0.026334	0.000000	9.808394	0.048629	0.090597	-0.033175
+11.066136	0.016758	0.014364	9.770089	0.049296	0.087933	-0.032908
+11.067135	0.021546	-0.007182	9.746149	0.047963	0.087400	-0.034374
+11.068116	0.009576	-0.023940	9.734179	0.047031	0.088066	-0.034907
+11.069126	-0.007182	-0.055063	9.779666	0.045965	0.087533	-0.036772
+11.070114	0.002394	-0.004788	9.794030	0.046364	0.086734	-0.036905
+11.071135	0.019152	-0.004788	9.868245	0.048230	0.085934	-0.036372
+11.072132	-0.043093	-0.057457	9.841911	0.048629	0.088332	-0.037571
+11.073136	-0.016758	-0.011970	9.762907	0.046897	0.087666	-0.036905
+11.074137	0.028729	0.016758	9.796424	0.048363	0.086734	-0.037305
+11.075132	0.016758	0.014364	9.841911	0.050095	0.090997	-0.035306
+11.076134	0.016758	0.014364	9.841911	0.047830	0.091263	-0.033974
+11.077132	0.059851	-0.007182	9.806000	0.046231	0.088732	-0.035972
+11.078123	0.023940	0.047881	9.815576	0.046498	0.087666	-0.037971
+11.079092	-0.004788	0.100550	9.798818	0.048363	0.085401	-0.036505
+11.080132	-0.009576	0.016758	9.782060	0.047830	0.085801	-0.035440
+11.081133	-0.055063	-0.011970	9.846699	0.047697	0.087400	-0.036772
+11.082137	-0.040699	-0.002394	9.829940	0.045565	0.089132	-0.036505
+11.083134	-0.023940	0.011970	9.765301	0.045432	0.089798	-0.034507
+11.084134	0.014364	-0.031123	9.743755	0.046897	0.089132	-0.036505
+11.085078	0.069427	-0.033517	9.774877	0.047564	0.088599	-0.035173
+11.086137	0.069427	0.031123	9.755725	0.047963	0.086201	-0.033974
+11.087127	0.050275	-0.007182	9.806000	0.046897	0.085534	-0.040502
+11.088101	0.004788	-0.093368	9.784454	0.046098	0.087933	-0.038104
+11.089164	-0.069427	-0.016758	9.794030	0.046764	0.089931	-0.036905
+11.090054	0.050275	0.016758	9.762907	0.047164	0.087666	-0.037971
+11.091127	0.050275	0.011970	9.810788	0.049162	0.087666	-0.035573
+11.092133	0.067033	0.009576	9.827546	0.048896	0.087933	-0.032908
+11.093134	0.050275	0.007182	9.849093	0.048096	0.089531	-0.037571
+11.094112	0.045487	-0.004788	9.717420	0.047963	0.088732	-0.039170
+11.095065	0.009576	-0.040699	9.758119	0.047564	0.089265	-0.041968
+11.096127	0.021546	-0.011970	9.777271	0.044499	0.087533	-0.039303
+11.097133	0.035911	0.021546	9.746149	0.041968	0.084069	-0.035839
+11.098116	0.021546	0.019152	9.758119	0.041568	0.086867	-0.036372
+11.099116	-0.028729	0.007182	9.782060	0.043167	0.089132	-0.036639
+11.100133	0.016758	-0.062245	9.789242	0.047963	0.088066	-0.038371
+11.101080	0.043093	-0.081397	9.786848	0.049828	0.088332	-0.036372
+11.102114	0.009576	-0.035911	9.827546	0.049695	0.090730	-0.034374
+11.103134	0.050275	0.000000	9.825152	0.048763	0.092063	-0.033441
+11.104129	0.057457	0.026334	9.700662	0.043567	0.089132	-0.034507
+11.105130	0.014364	0.050275	9.798818	0.045165	0.088466	-0.035706
+11.106117	-0.004788	0.028729	9.738967	0.047297	0.087400	-0.037438
+11.107132	-0.031123	-0.009576	9.789242	0.046897	0.085801	-0.035440
+11.108121	0.019152	-0.007182	9.863457	0.049695	0.088066	-0.035440
+11.109128	0.016758	-0.033517	9.834729	0.047963	0.089265	-0.036905
+11.110116	0.009576	0.014364	9.841911	0.047297	0.088865	-0.038371
+11.111135	0.055063	-0.009576	9.916126	0.048096	0.089132	-0.039303
+11.112133	-0.014364	0.045487	9.806000	0.046897	0.088599	-0.038371
+11.113133	0.007182	0.011970	9.748543	0.045832	0.089931	-0.033308
+11.114137	0.076609	0.002394	9.722208	0.048230	0.090064	-0.030910
+11.115078	0.074215	-0.021546	9.724603	0.048363	0.090064	-0.035040
+11.116132	-0.033517	-0.038305	9.815576	0.046631	0.087799	-0.036106
+11.117133	-0.028729	-0.052669	9.710238	0.046098	0.085135	-0.034374
+11.118085	0.059851	0.014364	9.743755	0.045832	0.085668	-0.034107
+11.119120	0.016758	-0.002394	9.815576	0.048629	0.087799	-0.036639
+11.120134	-0.002394	-0.062245	9.736573	0.050761	0.088599	-0.036905
+11.121134	0.004788	-0.009576	9.741361	0.050361	0.087400	-0.037172
+11.122137	-0.031123	0.007182	9.822758	0.047031	0.086067	-0.035306
+11.123131	-0.040699	0.023940	9.846699	0.046498	0.087133	-0.032109
+11.124134	-0.040699	0.035911	9.853881	0.047031	0.090064	-0.031975
+11.125060	-0.011970	0.007182	9.789242	0.048096	0.089798	-0.036106
+11.126135	0.050275	0.004788	9.825152	0.044766	0.085801	-0.037838
+11.127118	0.043093	0.000000	9.762907	0.043300	0.085534	-0.040769
+11.128125	0.007182	0.047881	9.789242	0.045032	0.088599	-0.038637
+11.129129	0.033517	0.038305	9.801212	0.047430	0.088466	-0.035440
+11.130135	0.045487	-0.026334	9.717420	0.049429	0.087666	-0.035573
+11.131128	-0.016758	0.014364	9.791636	0.048363	0.087666	-0.033708
+11.132133	0.067033	0.035911	9.817970	0.048096	0.086334	-0.035440
+11.133132	0.011970	-0.047881	9.832334	0.047697	0.086334	-0.035573
+11.134134	-0.019152	-0.023940	9.796424	0.047963	0.087000	-0.034640
+11.135134	0.009576	-0.016758	9.844305	0.047297	0.085002	-0.035440
+11.136134	0.033517	0.009576	9.815576	0.046897	0.088066	-0.036372
+11.137133	0.004788	0.026334	9.837123	0.047430	0.089665	-0.038504
+11.138106	0.002394	0.019152	9.806000	0.046631	0.087000	-0.039703
+11.139134	0.040699	0.021546	9.820364	0.045698	0.086201	-0.037838
+11.140037	-0.011970	0.004788	9.892186	0.045165	0.085534	-0.037038
+11.141132	-0.045487	0.009576	9.853881	0.045965	0.085135	-0.036372
+11.142078	-0.021546	-0.011970	9.868245	0.045965	0.087133	-0.035173
+11.143094	-0.009576	0.007182	9.889792	0.045432	0.088732	-0.034907
+11.144131	0.023940	0.004788	9.863457	0.044366	0.088732	-0.035706
+11.145099	0.083792	-0.040699	9.913732	0.046764	0.090597	-0.038237
+11.146135	0.079003	0.002394	9.870639	0.049029	0.090331	-0.038371
+11.147133	0.067033	0.028729	9.806000	0.049562	0.087799	-0.036239
+11.148057	0.019152	0.000000	9.772483	0.049162	0.088865	-0.033574
+11.149068	0.009576	0.040699	9.796424	0.047830	0.086867	-0.037704
+11.150068	-0.031123	0.011970	9.786848	0.046631	0.087533	-0.039570
+11.151134	-0.035911	-0.047881	9.767695	0.046231	0.087266	-0.036505
+11.152134	0.019152	-0.023940	9.853881	0.048763	0.086867	-0.037305
+11.153128	0.040699	-0.002394	9.829940	0.049029	0.088865	-0.038904
+11.154131	0.011970	-0.043093	9.748543	0.045299	0.089132	-0.034507
+11.155133	-0.004788	0.019152	9.863457	0.043034	0.084868	-0.033708
+11.156134	-0.050275	0.009576	9.892186	0.044366	0.087933	-0.033841
+11.157134	-0.009576	-0.045487	9.834729	0.047031	0.089531	-0.037038
+11.158108	0.055063	-0.047881	9.774877	0.046764	0.088865	-0.036905
+11.159110	0.031123	-0.031123	9.808394	0.046631	0.088998	-0.036505
+11.160135	0.067033	-0.045487	9.798818	0.044766	0.088998	-0.037038
+11.161135	0.064639	-0.002394	9.834729	0.046231	0.087266	-0.036372
+11.162131	0.033517	0.059851	9.841911	0.049029	0.086734	-0.035440
+11.163121	0.011970	-0.028729	9.825152	0.049562	0.088466	-0.036505
+11.164068	-0.040699	-0.074215	9.853881	0.047830	0.090464	-0.035839
+11.165127	0.035911	-0.028729	9.825152	0.044766	0.089132	-0.035306
+11.166098	-0.016758	-0.011970	9.760513	0.043966	0.087266	-0.037305
+11.167136	-0.009576	-0.023940	9.798818	0.047963	0.088466	-0.039303
+11.168129	0.004788	0.033517	9.825152	0.051827	0.087400	-0.040103
+11.169091	0.028729	0.019152	9.839517	0.048629	0.087533	-0.037038
+11.170070	-0.007182	-0.021546	9.846699	0.045698	0.087533	-0.037838
+11.171134	0.043093	-0.057457	9.772483	0.045032	0.088599	-0.033708
+11.172132	0.045487	0.014364	9.738967	0.045832	0.089398	-0.035706
+11.173134	0.007182	0.014364	9.834729	0.047031	0.091263	-0.036106
+11.174136	0.007182	-0.011970	9.810788	0.045165	0.090597	-0.035306
+11.175131	-0.004788	-0.033517	9.794030	0.046631	0.087799	-0.033708
+11.176134	-0.062245	0.023940	9.813182	0.049296	0.087533	-0.033841
+11.177102	-0.047881	0.026334	9.834729	0.047963	0.086867	-0.033308
+11.178127	0.002394	0.035911	9.782060	0.045698	0.086867	-0.036505
+11.179120	0.062245	-0.011970	9.719814	0.045432	0.088332	-0.035972
+11.180103	0.050275	0.021546	9.784454	0.046764	0.090730	-0.040369
+11.181137	0.028729	0.019152	9.738967	0.049429	0.089531	-0.039836
+11.182099	0.011970	-0.026334	9.806000	0.050095	0.085934	-0.037838
+11.183133	0.050275	-0.011970	9.794030	0.045565	0.085135	-0.037438
+11.184134	0.019152	-0.019152	9.782060	0.042634	0.083536	-0.037172
+11.185135	-0.004788	-0.023940	9.829940	0.043034	0.084868	-0.035839
+11.186114	0.007182	0.011970	9.813182	0.044366	0.087666	-0.037971
+11.187086	0.026334	0.007182	9.784454	0.046364	0.088865	-0.037571
+11.188068	0.040699	0.016758	9.760513	0.046098	0.087666	-0.036106
+11.189071	0.045487	-0.031123	9.746149	0.046631	0.087266	-0.036639
+11.190119	-0.021546	-0.026334	9.765301	0.046364	0.086734	-0.035573
+11.191126	-0.028729	-0.040699	9.820364	0.045698	0.087133	-0.035972
+11.192194	-0.023940	0.026334	9.789242	0.045698	0.088066	-0.038237
+11.193128	0.000000	-0.021546	9.817970	0.046764	0.086734	-0.037838
+11.194150	0.045487	-0.016758	9.834729	0.049029	0.086734	-0.036772
+11.195193	0.035911	-0.028729	9.808394	0.045965	0.087933	-0.033841
+11.196193	0.050275	-0.011970	9.810788	0.043966	0.088332	-0.032775
+11.197193	0.031123	-0.026334	9.829940	0.045432	0.088599	-0.035706
+11.198174	-0.007182	-0.002394	9.851487	0.047697	0.089665	-0.036905
+11.199131	-0.016758	-0.004788	9.827546	0.047297	0.087133	-0.036372
+11.200186	-0.026334	0.016758	9.810788	0.048230	0.085534	-0.036106
+11.201131	0.007182	0.011970	9.820364	0.049429	0.088865	-0.037438
+11.202134	-0.014364	-0.002394	9.786848	0.049828	0.090464	-0.035839
+11.203192	-0.014364	0.014364	9.698268	0.047830	0.086467	-0.037038
+11.204192	-0.057457	-0.014364	9.777271	0.047031	0.085002	-0.038371
+11.205192	-0.023940	-0.021546	9.856275	0.047031	0.087666	-0.039037
+11.206193	0.007182	0.019152	9.815576	0.046098	0.090331	-0.038504
+11.207144	-0.052669	-0.016758	9.829940	0.043833	0.088066	-0.036239
+11.208151	-0.007182	0.000000	9.791636	0.047031	0.087666	-0.034507
+11.209193	0.004788	0.031123	9.789242	0.048629	0.086201	-0.034507
+11.210153	-0.059851	-0.004788	9.774877	0.047697	0.085534	-0.035573
+11.211191	0.019152	0.047881	9.798818	0.046631	0.084335	-0.034107
+11.212193	0.021546	0.079003	9.837123	0.047164	0.085801	-0.033175
+11.213194	-0.004788	0.011970	9.777271	0.048763	0.089398	-0.032375
+11.214197	0.002394	-0.023940	9.815576	0.048629	0.088998	-0.036106
+11.215150	-0.023940	0.028729	9.772483	0.047430	0.088599	-0.040369
+11.216163	0.000000	0.009576	9.844305	0.045432	0.089398	-0.036372
+11.217106	-0.007182	-0.009576	9.813182	0.044100	0.088066	-0.035173
+11.218147	0.014364	-0.038305	9.688692	0.045832	0.087133	-0.035306
+11.219187	-0.011970	-0.016758	9.782060	0.049162	0.085002	-0.034773
+11.220194	0.002394	-0.011970	9.758119	0.050228	0.087133	-0.033708
+11.221191	0.000000	-0.002394	9.774877	0.047430	0.089265	-0.035040
+11.222194	0.004788	0.059851	9.719814	0.046098	0.089531	-0.036772
+11.223193	-0.033517	0.007182	9.782060	0.046098	0.087799	-0.040502
+11.224194	0.021546	-0.098156	9.760513	0.045565	0.088599	-0.039836
+11.225139	0.055063	-0.064639	9.827546	0.046231	0.088998	-0.035040
+11.226107	0.026334	-0.040699	9.767695	0.048363	0.090331	-0.035173
+11.227187	-0.040699	0.038305	9.729391	0.048763	0.090064	-0.035706
+11.228168	-0.045487	0.083792	9.748543	0.049695	0.086334	-0.035440
+11.229155	-0.004788	0.019152	9.734179	0.046764	0.087933	-0.036372
+11.230122	-0.011970	-0.038305	9.789242	0.044899	0.088599	-0.033974
+11.231202	0.052669	-0.016758	9.777271	0.044899	0.084868	-0.036106
+11.232195	0.035911	0.002394	9.789242	0.046498	0.083936	-0.039703
+11.233132	0.009576	-0.011970	9.839517	0.048496	0.088199	-0.040636
+11.234116	0.019152	0.038305	9.820364	0.048230	0.089665	-0.037438
+11.235137	-0.055063	0.016758	9.846699	0.045565	0.087000	-0.035972
+11.236156	-0.043093	-0.004788	9.817970	0.046098	0.086467	-0.034240
+11.237194	0.009576	-0.026334	9.770089	0.047164	0.088998	-0.035706
+11.238142	0.000000	-0.026334	9.849093	0.047697	0.088865	-0.037438
+11.239124	0.002394	-0.014364	9.851487	0.046764	0.089798	-0.038637
+11.240118	-0.004788	0.023940	9.834729	0.045698	0.089931	-0.038504
+11.241113	0.026334	-0.009576	9.801212	0.046897	0.090864	-0.038237
+11.242130	0.014364	-0.007182	9.825152	0.047164	0.089931	-0.038504
+11.243122	-0.002394	-0.038305	9.856275	0.045965	0.087666	-0.039703
+11.244127	0.031123	-0.033517	9.772483	0.048230	0.087266	-0.039570
+11.245126	0.000000	-0.031123	9.784454	0.048763	0.088732	-0.037971
+11.246149	0.016758	0.009576	9.846699	0.049562	0.091397	-0.039170
+11.247187	0.009576	0.064639	9.868245	0.050228	0.088998	-0.039969
+11.248193	0.033517	-0.004788	9.846699	0.047830	0.086467	-0.037038
+11.249126	0.052669	-0.047881	9.851487	0.047430	0.086467	-0.036905
+11.250121	0.026334	-0.040699	9.892186	0.047963	0.087533	-0.037971
+11.251121	0.064639	0.007182	9.803606	0.047164	0.089398	-0.035040
+11.252192	0.007182	0.000000	9.827546	0.043833	0.087533	-0.035040
+11.253191	0.004788	0.038305	9.892186	0.045565	0.086867	-0.032242
+11.254163	0.052669	-0.016758	9.849093	0.047697	0.086067	-0.034374
+11.255149	0.016758	-0.019152	9.841911	0.047031	0.088066	-0.034773
+11.256190	0.062245	0.023940	9.777271	0.046498	0.091663	-0.032375
+11.257193	0.043093	0.004788	9.789242	0.045965	0.093262	-0.036106
+11.258197	-0.014364	-0.045487	9.918520	0.047830	0.090064	-0.037172
+11.259137	-0.016758	-0.035911	9.770089	0.048363	0.088332	-0.035040
+11.260099	0.026334	0.021546	9.741361	0.048629	0.086334	-0.032508
+11.261121	-0.019152	-0.002394	9.758119	0.046764	0.084202	-0.032775
+11.262122	-0.040699	0.002394	9.770089	0.045565	0.088732	-0.035839
+11.263191	0.011970	0.050275	9.808394	0.046764	0.089531	-0.038104
+11.264149	-0.004788	-0.014364	9.779666	0.047830	0.088865	-0.037971
+11.265188	0.011970	-0.038305	9.777271	0.047031	0.084735	-0.038770
+11.266137	0.067033	-0.021546	9.806000	0.047564	0.087533	-0.035706
+11.267191	0.071821	-0.043093	9.758119	0.046897	0.089798	-0.037704
+11.268192	-0.011970	-0.011970	9.789242	0.046631	0.091130	-0.037172
+11.269148	-0.014364	-0.023940	9.820364	0.046498	0.086201	-0.039436
+11.270141	-0.014364	-0.019152	9.774877	0.046231	0.085268	-0.039037
+11.271128	0.004788	-0.021546	9.779666	0.048496	0.087133	-0.038104
+11.272127	0.059851	-0.026334	9.822758	0.048230	0.088466	-0.039969
+11.273129	0.009576	-0.026334	9.772483	0.046897	0.087266	-0.035706
+11.274129	-0.007182	-0.050275	9.789242	0.045965	0.086734	-0.035573
+11.275137	0.050275	-0.014364	9.798818	0.045832	0.086867	-0.037571
+11.276129	0.043093	0.000000	9.784454	0.046764	0.088732	-0.038904
+11.277134	0.076609	-0.019152	9.810788	0.046364	0.089531	-0.039303
+11.278134	-0.014364	0.002394	9.825152	0.047297	0.088466	-0.035440
+11.279130	-0.026334	0.004788	9.877821	0.048763	0.088332	-0.034374
+11.280133	-0.023940	0.007182	9.930490	0.045165	0.088066	-0.038504
+11.281192	0.019152	-0.031123	9.896974	0.045032	0.086867	-0.037704
+11.282163	-0.004788	-0.026334	9.846699	0.045698	0.087000	-0.037704
+11.283133	0.026334	-0.026334	9.870639	0.044766	0.088732	-0.036905
+11.284195	0.002394	-0.016758	9.801212	0.043700	0.087666	-0.034640
+11.285146	-0.004788	-0.019152	9.786848	0.044766	0.087266	-0.035839
+11.286196	-0.021546	-0.014364	9.796424	0.045032	0.086334	-0.035440
+11.287191	0.043093	-0.014364	9.777271	0.045432	0.086867	-0.036106
+11.288133	0.064639	-0.004788	9.892186	0.048230	0.089798	-0.037571
+11.289191	0.021546	0.023940	9.798818	0.047430	0.089265	-0.036372
+11.290194	0.019152	0.021546	9.789242	0.045032	0.086734	-0.037038
+11.291108	0.026334	-0.055063	9.738967	0.046498	0.087266	-0.036772
+11.292119	0.016758	-0.047881	9.829940	0.047697	0.088998	-0.037838
+11.293097	0.009576	-0.009576	9.880215	0.045432	0.086600	-0.035040
+11.294120	0.002394	0.007182	9.779666	0.045698	0.084735	-0.038504
+11.295120	-0.043093	0.009576	9.765301	0.046098	0.084868	-0.036239
+11.296120	-0.014364	0.016758	9.841911	0.046631	0.088199	-0.034507
+11.297121	-0.009576	-0.023940	9.849093	0.047564	0.088599	-0.032375
+11.298116	-0.007182	0.014364	9.772483	0.048230	0.089132	-0.033574
+11.299119	0.007182	0.023940	9.827546	0.048896	0.089931	-0.036905
+11.300118	0.050275	0.014364	9.896974	0.047697	0.090198	-0.038904
+11.301115	0.050275	0.009576	9.916126	0.047697	0.088466	-0.038904
+11.302123	-0.004788	0.007182	9.863457	0.047164	0.089798	-0.037971
+11.303119	-0.023940	0.011970	9.861063	0.045432	0.090597	-0.034773
+11.304121	-0.011970	0.040699	9.798818	0.045698	0.089132	-0.038104
+11.305101	0.011970	-0.002394	9.758119	0.047697	0.087400	-0.038770
+11.306041	0.040699	0.050275	9.796424	0.049029	0.089132	-0.036106
+11.307063	0.019152	0.038305	9.808394	0.048230	0.088599	-0.036106
+11.308048	0.011970	0.023940	9.815576	0.046098	0.088599	-0.038504
+11.309053	0.067033	-0.019152	9.806000	0.044766	0.087000	-0.038504
+11.310053	0.055063	-0.076609	9.755725	0.045565	0.088332	-0.037704
+11.311052	0.033517	-0.014364	9.841911	0.047164	0.087133	-0.036772
+11.312054	-0.045487	0.002394	9.894580	0.048096	0.085135	-0.036239
+11.313054	-0.011970	-0.074215	9.865851	0.046897	0.085801	-0.038637
+11.314053	0.026334	-0.019152	9.880215	0.047963	0.088466	-0.034240
+11.315052	0.016758	0.021546	9.777271	0.050095	0.091796	-0.033974
+11.316085	0.004788	-0.031123	9.820364	0.047830	0.088865	-0.037571
+11.317091	-0.023940	0.007182	9.844305	0.046098	0.088599	-0.038904
+11.318075	0.028729	0.059851	9.825152	0.046364	0.089398	-0.037704
+11.319065	0.016758	0.021546	9.853881	0.047963	0.088998	-0.036239
+11.320082	0.009576	-0.019152	9.844305	0.047164	0.089265	-0.034640
+11.321059	-0.019152	-0.004788	9.786848	0.046764	0.090464	-0.037172
+11.322134	0.000000	-0.035911	9.827546	0.046098	0.087000	-0.036639
+11.323132	0.004788	-0.004788	9.755725	0.044899	0.088599	-0.034240
+11.324132	-0.004788	-0.019152	9.693480	0.046364	0.090464	-0.036372
+11.325131	0.009576	0.035911	9.798818	0.047031	0.087266	-0.035440
+11.326104	0.033517	0.028729	9.815576	0.045832	0.086734	-0.035573
+11.327131	0.055063	-0.019152	9.803606	0.044100	0.088466	-0.036639
+11.328094	0.016758	-0.004788	9.832334	0.045299	0.087799	-0.036106
+11.329127	-0.014364	-0.023940	9.786848	0.046631	0.086600	-0.034240
+11.330128	0.019152	0.016758	9.777271	0.049296	0.087933	-0.032908
+11.331054	0.021546	-0.033517	9.789242	0.049962	0.088599	-0.036505
+11.332063	0.038305	-0.011970	9.794030	0.047430	0.086867	-0.038904
+11.333131	0.009576	-0.047881	9.865851	0.046897	0.086867	-0.036772
+11.334134	-0.059851	-0.004788	9.841911	0.047164	0.088732	-0.037038
+11.335097	-0.026334	-0.033517	9.772483	0.047830	0.088199	-0.038104
+11.336131	-0.076609	-0.011970	9.777271	0.045565	0.087000	-0.037571
+11.337131	-0.057457	-0.009576	9.770089	0.045165	0.087266	-0.036772
+11.338120	0.002394	0.007182	9.748543	0.048629	0.088732	-0.037038
+11.339058	0.045487	0.002394	9.798818	0.047297	0.088199	-0.036372
+11.340064	0.035911	0.000000	9.851487	0.045832	0.084602	-0.035440
+11.341101	0.074215	-0.045487	9.801212	0.045299	0.085934	-0.038504
+11.342134	0.033517	-0.031123	9.772483	0.046498	0.088732	-0.037704
+11.343131	0.002394	-0.059851	9.796424	0.048496	0.090730	-0.034107
+11.344122	0.023940	0.019152	9.839517	0.045032	0.090331	-0.036239
+11.345135	-0.045487	0.045487	9.825152	0.042101	0.087533	-0.039037
+11.346141	0.019152	-0.026334	9.822758	0.044100	0.087133	-0.039436
+11.347193	0.040699	-0.019152	9.772483	0.047564	0.085002	-0.037971
+11.348130	0.052669	-0.009576	9.825152	0.049562	0.085268	-0.038637
+11.349193	0.023940	-0.023940	9.765301	0.050095	0.086067	-0.037038
+11.350130	-0.033517	-0.028729	9.791636	0.049695	0.087533	-0.036639
+11.351190	-0.004788	0.002394	9.736573	0.049162	0.088599	-0.035706
+11.352189	0.011970	-0.038305	9.827546	0.048230	0.089531	-0.039303
+11.353190	0.052669	-0.067033	9.817970	0.047564	0.088066	-0.037172
+11.354194	0.069427	0.016758	9.712632	0.045965	0.085401	-0.036639
+11.355192	0.016758	-0.023940	9.734179	0.047963	0.088466	-0.037704
+11.356150	0.016758	-0.040699	9.748543	0.049429	0.090864	-0.036505
+11.357156	-0.057457	0.009576	9.813182	0.047031	0.090331	-0.036106
+11.358195	-0.076609	0.021546	9.810788	0.045698	0.089265	-0.033574
+11.359191	-0.014364	0.019152	9.870639	0.045032	0.088998	-0.034374
+11.360190	0.038305	-0.019152	9.834729	0.044766	0.090331	-0.036505
+11.361193	0.045487	-0.009576	9.810788	0.046498	0.089665	-0.035972
+11.362128	0.004788	0.011970	9.837123	0.047564	0.086467	-0.037838
+11.363189	0.007182	-0.019152	9.817970	0.049429	0.086467	-0.036772
+11.364189	-0.038305	-0.057457	9.808394	0.046498	0.088599	-0.036505
+11.365202	-0.040699	-0.023940	9.794030	0.045565	0.088865	-0.036106
+11.366129	0.002394	-0.009576	9.789242	0.046231	0.088332	-0.038104
+11.367192	-0.014364	-0.045487	9.808394	0.048896	0.087666	-0.037571
+11.368191	-0.004788	-0.045487	9.796424	0.050894	0.088732	-0.034640
+11.369130	0.031123	-0.045487	9.777271	0.049162	0.092063	-0.035440
+11.370120	0.007182	-0.067033	9.829940	0.049828	0.088998	-0.033974
+11.371190	-0.007182	0.009576	9.813182	0.047697	0.085401	-0.031576
+11.372189	-0.021546	-0.035911	9.853881	0.045432	0.085801	-0.032908
+11.373190	-0.038305	-0.057457	9.784454	0.045832	0.087266	-0.036639
+11.374160	0.021546	-0.050275	9.834729	0.047963	0.087133	-0.033441
+11.375134	0.031123	0.014364	9.827546	0.048363	0.085268	-0.035040
+11.376198	-0.033517	-0.040699	9.772483	0.047830	0.085401	-0.039836
+11.377190	-0.043093	-0.062245	9.789242	0.048096	0.088332	-0.043034
+11.378196	0.011970	-0.014364	9.841911	0.047297	0.088732	-0.039836
+11.379190	0.031123	0.021546	9.820364	0.044100	0.089132	-0.035040
+11.380132	0.009576	0.004788	9.813182	0.044100	0.089132	-0.035573
+11.381189	-0.028729	0.009576	9.820364	0.046498	0.087133	-0.034907
+11.382108	-0.016758	-0.004788	9.841911	0.046897	0.088732	-0.034107
+11.383117	0.019152	-0.043093	9.841911	0.046098	0.090730	-0.035972
+11.384126	-0.002394	-0.019152	9.815576	0.045299	0.090864	-0.033175
+11.385074	0.083792	0.000000	9.772483	0.047297	0.088199	-0.036905
+11.386131	0.059851	-0.011970	9.784454	0.047697	0.088066	-0.035306
+11.387111	0.002394	-0.038305	9.784454	0.045832	0.089665	-0.035706
+11.388093	0.050275	-0.026334	9.820364	0.047164	0.088998	-0.034240
+11.389097	0.059851	-0.011970	9.743755	0.047697	0.091130	-0.034507
+11.390042	0.009576	-0.016758	9.760513	0.045565	0.090464	-0.037172
+11.391086	0.007182	-0.028729	9.806000	0.046364	0.091530	-0.037571
+11.392060	0.000000	0.002394	9.813182	0.048629	0.090331	-0.035706
+11.393066	0.004788	-0.002394	9.856275	0.046231	0.087933	-0.036106
+11.394067	0.040699	-0.009576	9.834729	0.048096	0.087000	-0.033041
+11.395088	0.067033	0.007182	9.794030	0.047830	0.086201	-0.035972
+11.396089	0.011970	0.052669	9.777271	0.045032	0.087933	-0.038770
+11.397050	-0.040699	0.045487	9.798818	0.045032	0.085668	-0.036639
+11.398085	-0.045487	0.038305	9.741361	0.046364	0.083669	-0.038637
+11.399127	0.009576	0.016758	9.767695	0.045832	0.085534	-0.035972
+11.400093	0.019152	0.043093	9.794030	0.047430	0.089265	-0.036239
+11.401134	0.031123	0.009576	9.731785	0.049562	0.085801	-0.034107
+11.402063	0.028729	-0.040699	9.796424	0.049429	0.086734	-0.035972
+11.403134	0.055063	-0.086186	9.808394	0.048763	0.090064	-0.037571
+11.404131	0.083792	-0.040699	9.796424	0.045165	0.089132	-0.039303
+11.405133	0.095762	-0.016758	9.849093	0.042900	0.088199	-0.039836
+11.406095	0.026334	0.004788	9.798818	0.045965	0.087533	-0.037438
+11.407057	-0.023940	0.021546	9.813182	0.046364	0.088998	-0.034907
+11.408067	0.000000	0.035911	9.753331	0.045565	0.090464	-0.032908
+11.409065	0.000000	0.007182	9.762907	0.047297	0.089931	-0.034240
+11.410068	-0.047881	0.016758	9.784454	0.047697	0.090198	-0.035440
+11.411134	0.019152	0.000000	9.760513	0.046897	0.091263	-0.035440
+11.412136	-0.011970	0.016758	9.741361	0.048363	0.090064	-0.036505
+11.413102	-0.009576	0.002394	9.755725	0.049828	0.087933	-0.035972
+11.414117	-0.019152	-0.007182	9.806000	0.048896	0.087666	-0.038504
+11.415134	-0.007182	-0.055063	9.765301	0.049429	0.089531	-0.038770
+11.416134	0.004788	-0.045487	9.825152	0.048763	0.086467	-0.036372
+11.417129	0.021546	-0.033517	9.820364	0.047963	0.088199	-0.036505
+11.418070	0.016758	-0.007182	9.815576	0.048230	0.090064	-0.036905
+11.419132	0.004788	-0.014364	9.813182	0.048496	0.089798	-0.038104
+11.420119	-0.040699	-0.059851	9.825152	0.047830	0.087666	-0.035440
+11.421083	0.007182	0.002394	9.863457	0.047830	0.088599	-0.036505
+11.422086	-0.009576	-0.004788	9.806000	0.047564	0.086201	-0.034507
+11.423088	-0.009576	-0.021546	9.789242	0.049962	0.087266	-0.035040
+11.424083	0.035911	-0.035911	9.880215	0.049296	0.091397	-0.038371
+11.425072	0.028729	-0.031123	9.849093	0.049695	0.090331	-0.041568
+11.426056	-0.009576	0.035911	9.851487	0.047830	0.088599	-0.040103
+11.427055	0.004788	0.016758	9.798818	0.044632	0.089265	-0.037172
+11.428055	-0.007182	0.002394	9.825152	0.045832	0.088599	-0.036772
+11.429051	0.019152	-0.019152	9.841911	0.046098	0.087533	-0.036239
+11.430058	0.064639	0.009576	9.813182	0.046764	0.087533	-0.039836
+11.431057	0.031123	0.026334	9.791636	0.048629	0.088332	-0.039037
+11.432056	0.050275	-0.055063	9.815576	0.048629	0.088599	-0.037038
+11.433053	-0.014364	0.043093	9.810788	0.047031	0.087000	-0.037172
+11.434055	0.007182	0.062245	9.741361	0.045165	0.088066	-0.040369
+11.435055	0.000000	0.014364	9.662357	0.044632	0.088066	-0.037172
+11.436055	0.002394	-0.095762	9.758119	0.047697	0.086201	-0.033841
+11.437055	0.045487	-0.055063	9.753331	0.049695	0.087266	-0.034907
+11.438057	0.031123	-0.026334	9.772483	0.049828	0.087799	-0.035040
+11.439050	0.000000	0.004788	9.801212	0.048496	0.087799	-0.035839
+11.440057	-0.021546	-0.014364	9.813182	0.050228	0.088332	-0.040636
+11.441057	-0.011970	-0.045487	9.844305	0.048230	0.090597	-0.037704
+11.442100	0.043093	-0.057457	9.853881	0.045965	0.091397	-0.035706
+11.443097	0.000000	-0.014364	9.858669	0.046631	0.090864	-0.037172
+11.444096	-0.040699	0.014364	9.815576	0.045965	0.089798	-0.040502
+11.445097	-0.014364	-0.031123	9.894580	0.045832	0.088732	-0.039436
+11.446085	-0.014364	0.007182	9.822758	0.045832	0.088466	-0.039836
+11.447106	0.031123	0.002394	9.798818	0.045698	0.086201	-0.038371
+11.448085	-0.009576	-0.007182	9.707844	0.045032	0.085135	-0.037838
+11.449048	-0.023940	0.009576	9.738967	0.045299	0.085801	-0.039570
+11.450050	0.035911	-0.016758	9.825152	0.045832	0.086734	-0.037571
+11.451049	-0.016758	0.016758	9.798818	0.045698	0.087933	-0.035706
+11.452065	-0.002394	-0.031123	9.820364	0.048629	0.086201	-0.035706
+11.453066	0.031123	-0.007182	9.705450	0.049429	0.086867	-0.034374
+11.454067	0.047881	0.000000	9.765301	0.049828	0.088732	-0.037038
+11.455061	0.021546	-0.038305	9.810788	0.047830	0.090464	-0.035839
+11.456066	0.011970	-0.004788	9.784454	0.044499	0.090198	-0.036505
+11.457037	0.009576	-0.009576	9.806000	0.044632	0.089265	-0.034507
+11.458032	0.002394	-0.004788	9.753331	0.046897	0.087666	-0.036772
+11.459045	-0.019152	-0.016758	9.695874	0.048763	0.089931	-0.039836
+11.460053	-0.047881	-0.009576	9.719814	0.046764	0.090064	-0.038504
+11.461044	0.011970	0.021546	9.738967	0.048230	0.088466	-0.034240
+11.462050	-0.014364	-0.031123	9.841911	0.047031	0.087666	-0.033041
+11.463048	0.031123	-0.043093	9.822758	0.046364	0.089531	-0.036639
+11.464043	0.043093	-0.038305	9.837123	0.047297	0.089931	-0.039570
+11.465019	-0.021546	-0.019152	9.782060	0.049162	0.090864	-0.034640
+11.466050	0.007182	-0.035911	9.743755	0.048629	0.090331	-0.033041
+11.467047	-0.004788	-0.033517	9.707844	0.047297	0.090464	-0.035972
+11.468058	-0.040699	0.021546	9.729391	0.045965	0.087666	-0.037838
+11.469035	-0.011970	0.011970	9.695874	0.046631	0.085934	-0.037838
+11.470102	0.031123	-0.009576	9.715026	0.046897	0.088466	-0.038504
+11.471094	-0.021546	-0.007182	9.770089	0.047297	0.089931	-0.038371
+11.472104	0.026334	0.064639	9.853881	0.048896	0.088732	-0.039170
+11.473093	0.019152	0.045487	9.774877	0.047564	0.091397	-0.037438
+11.474053	-0.014364	0.033517	9.885003	0.047297	0.088466	-0.035440
+11.475053	0.000000	-0.002394	9.772483	0.047697	0.088599	-0.034907
+11.476031	0.021546	-0.023940	9.779666	0.047031	0.090464	-0.034374
+11.477023	0.064639	0.026334	9.837123	0.047031	0.090064	-0.035040
+11.478028	0.047881	-0.071821	9.868245	0.046364	0.086467	-0.032242
+11.479027	0.062245	-0.047881	9.810788	0.045698	0.087000	-0.033041
+11.480029	0.081397	-0.009576	9.837123	0.046498	0.085801	-0.033175
+11.481003	0.019152	-0.033517	9.858669	0.047963	0.086334	-0.037172
+11.482027	-0.023940	-0.052669	9.798818	0.047564	0.087533	-0.038504
+11.483030	0.033517	0.016758	9.844305	0.046498	0.088732	-0.033574
+11.484050	0.014364	0.019152	9.777271	0.047031	0.088466	-0.035573
+11.485048	0.028729	-0.011970	9.846699	0.049296	0.089398	-0.038371
+11.486070	0.002394	0.038305	9.856275	0.049695	0.088998	-0.036106
+11.487057	0.014364	0.059851	9.803606	0.048629	0.087933	-0.034240
+11.488038	-0.043093	0.057457	9.705450	0.046764	0.087933	-0.035173
+11.489013	-0.026334	0.074215	9.770089	0.046364	0.088466	-0.034640
+11.490035	-0.004788	0.000000	9.849093	0.047031	0.090597	-0.038770
+11.491038	0.023940	0.028729	9.851487	0.048896	0.088732	-0.035972
+11.492034	-0.023940	-0.023940	9.762907	0.048629	0.088865	-0.035306
+11.493042	0.047881	-0.016758	9.770089	0.047564	0.089531	-0.036106
+11.494043	0.031123	0.009576	9.815576	0.046498	0.090198	-0.039703
+11.495033	0.023940	-0.026334	9.810788	0.045165	0.086600	-0.037038
+11.496033	0.000000	-0.052669	9.851487	0.045698	0.087400	-0.036905
+11.497009	0.009576	-0.098156	9.882609	0.047564	0.090730	-0.037438
+11.498028	0.011970	-0.004788	9.829940	0.048896	0.088199	-0.037305
+11.499025	0.004788	0.021546	9.786848	0.049296	0.086867	-0.034640
+11.499999	0.019152	-0.026334	9.796424	0.045965	0.085934	-0.035972
+11.501050	0.043093	-0.016758	9.796424	0.041701	0.085401	-0.038371
+11.502083	0.000000	-0.031123	9.715026	0.044632	0.088466	-0.039170
+11.503080	-0.016758	-0.047881	9.717420	0.049162	0.089132	-0.035040
+11.504128	-0.004788	-0.011970	9.875427	0.052227	0.088732	-0.035040
+11.505106	0.023940	-0.033517	9.935278	0.049296	0.088998	-0.037038
+11.506114	-0.021546	-0.028729	9.813182	0.046498	0.088599	-0.037971
+11.507107	-0.009576	-0.007182	9.810788	0.046364	0.086734	-0.038237
+11.508104	0.052669	0.007182	9.889792	0.047564	0.087400	-0.036905
+11.509104	0.026334	-0.011970	9.849093	0.046764	0.086334	-0.035972
+11.510052	0.026334	-0.021546	9.753331	0.049029	0.086334	-0.037305
+11.511123	-0.014364	-0.055063	9.846699	0.047564	0.087533	-0.037838
+11.512125	-0.002394	-0.050275	9.841911	0.045565	0.087933	-0.034773
+11.513107	0.019152	-0.004788	9.827546	0.044499	0.088466	-0.036772
+11.514106	0.040699	-0.026334	9.772483	0.045698	0.089665	-0.036905
+11.515107	0.043093	-0.023940	9.849093	0.047963	0.088199	-0.037438
+11.516105	0.052669	-0.047881	9.806000	0.047164	0.086334	-0.038237
+11.517039	0.035911	-0.031123	9.832334	0.046498	0.085801	-0.035440
+11.518108	0.011970	0.028729	9.834729	0.046631	0.087133	-0.032375
+11.519101	0.007182	0.007182	9.803606	0.047430	0.086067	-0.036372
+11.520086	0.031123	-0.038305	9.815576	0.047830	0.089798	-0.035306
+11.521083	0.035911	-0.021546	9.796424	0.047697	0.092329	-0.033308
+11.522105	0.019152	-0.033517	9.810788	0.047564	0.088998	-0.036372
+11.523105	0.007182	-0.016758	9.889792	0.047963	0.084469	-0.037571
+11.524056	-0.033517	-0.043093	9.803606	0.047697	0.085668	-0.034507
+11.525050	-0.009576	0.004788	9.798818	0.047430	0.087933	-0.031309
+11.526060	0.045487	0.019152	9.750937	0.048363	0.089132	-0.031576
+11.527071	0.004788	-0.004788	9.719814	0.048629	0.087533	-0.034773
+11.528106	-0.011970	-0.019152	9.789242	0.049296	0.086201	-0.034907
+11.529105	0.035911	-0.026334	9.762907	0.047430	0.085801	-0.033441
+11.530065	0.007182	-0.007182	9.911338	0.046498	0.089265	-0.033441
+11.531097	0.028729	0.007182	9.885003	0.047830	0.090864	-0.036639
+11.532065	0.038305	-0.004788	9.829940	0.047697	0.090997	-0.035706
+11.533078	0.047881	0.050275	9.774877	0.048496	0.089665	-0.037704
+11.534033	0.047881	0.045487	9.794030	0.047830	0.089531	-0.037438
+11.535057	0.009576	0.019152	9.849093	0.046098	0.087266	-0.035972
+11.536099	-0.011970	0.016758	9.806000	0.044366	0.087266	-0.035040
+11.537105	-0.007182	-0.009576	9.794030	0.046764	0.088998	-0.034507
+11.538054	0.035911	-0.002394	9.825152	0.047564	0.089665	-0.034907
+11.539071	-0.009576	-0.019152	9.820364	0.046231	0.089798	-0.033708
+11.540071	0.014364	-0.021546	9.844305	0.046364	0.088599	-0.034773
+11.541045	-0.035911	-0.009576	9.820364	0.046764	0.086734	-0.039303
+11.542056	-0.035911	0.016758	9.856275	0.047430	0.086467	-0.041302
+11.543103	0.052669	0.014364	9.796424	0.048230	0.088732	-0.036372
+11.544075	0.043093	-0.026334	9.729391	0.045698	0.088199	-0.034507
+11.545096	0.023940	0.011970	9.791636	0.045832	0.087533	-0.041302
+11.546080	-0.033517	-0.033517	9.810788	0.047564	0.087133	-0.037971
+11.547103	-0.011970	-0.040699	9.791636	0.047164	0.085668	-0.035173
+11.548105	0.016758	-0.011970	9.806000	0.046098	0.086067	-0.034907
+11.549041	0.014364	0.014364	9.885003	0.046364	0.085401	-0.036239
+11.550108	-0.009576	0.007182	9.789242	0.047297	0.086734	-0.036505
+11.551046	-0.038305	0.045487	9.762907	0.045565	0.089665	-0.035972
+11.552103	-0.014364	0.009576	9.796424	0.045565	0.091130	-0.037438
+11.553106	-0.016758	-0.038305	9.822758	0.046098	0.090997	-0.039436
+11.554097	0.023940	-0.011970	9.786848	0.047564	0.089531	-0.037038
+11.555046	0.031123	0.031123	9.801212	0.050761	0.089398	-0.035306
+11.556042	0.014364	0.007182	9.810788	0.048896	0.087533	-0.036905
+11.557055	0.011970	-0.002394	9.820364	0.044632	0.085268	-0.037838
+11.558100	0.035911	-0.004788	9.817970	0.044766	0.087933	-0.035839
+11.559104	0.033517	-0.019152	9.834729	0.047564	0.087666	-0.036505
+11.560105	-0.014364	-0.011970	9.774877	0.047830	0.088066	-0.035306
+11.561104	-0.026334	-0.026334	9.750937	0.047031	0.087533	-0.034907
+11.562100	0.035911	0.004788	9.734179	0.046764	0.086867	-0.034907
+11.563105	-0.007182	-0.031123	9.772483	0.047031	0.088466	-0.037704
+11.564078	-0.023940	-0.038305	9.772483	0.045965	0.090198	-0.039570
+11.565097	0.016758	-0.014364	9.825152	0.046631	0.087933	-0.037571
+11.566107	-0.033517	-0.045487	9.827546	0.046764	0.085668	-0.039436
+11.567100	-0.026334	-0.047881	9.846699	0.049429	0.087799	-0.039570
+11.568103	-0.031123	-0.028729	9.877821	0.050361	0.089132	-0.037172
+11.569106	-0.093368	0.014364	9.837123	0.048896	0.088998	-0.035306
+11.570061	-0.038305	-0.043093	9.765301	0.048096	0.090331	-0.035839
+11.571104	0.004788	-0.050275	9.729391	0.047031	0.091663	-0.035706
+11.572105	0.016758	-0.019152	9.798818	0.047031	0.090730	-0.033974
+11.573105	0.033517	-0.016758	9.820364	0.047697	0.088066	-0.034374
+11.574084	-0.023940	-0.038305	9.784454	0.049162	0.087933	-0.035706
+11.575100	-0.014364	-0.019152	9.789242	0.047164	0.087666	-0.035173
+11.576102	-0.079003	0.002394	9.810788	0.046897	0.089531	-0.037838
+11.577109	-0.023940	0.021546	9.868245	0.047830	0.089531	-0.035706
+11.578107	0.009576	0.035911	9.765301	0.048363	0.086201	-0.035440
+11.579101	-0.023940	0.035911	9.762907	0.047564	0.084335	-0.036239
+11.580105	-0.011970	-0.009576	9.782060	0.045432	0.084735	-0.036372
+11.581103	0.007182	-0.007182	9.782060	0.045965	0.086067	-0.034640
+11.582106	0.064639	0.014364	9.825152	0.048096	0.088466	-0.038237
+11.583102	-0.011970	-0.016758	9.767695	0.045965	0.089265	-0.037838
+11.584073	-0.035911	-0.033517	9.822758	0.044233	0.088466	-0.037971
+11.585125	-0.019152	-0.064639	9.849093	0.044499	0.089931	-0.038371
+11.586106	0.021546	-0.035911	9.849093	0.045698	0.089665	-0.037838
+11.587103	0.002394	-0.019152	9.861063	0.048230	0.087533	-0.036772
+11.588099	0.028729	0.043093	9.923308	0.048230	0.086600	-0.036772
+11.589108	-0.059851	-0.002394	9.901762	0.047031	0.088066	-0.035839
+11.590106	-0.038305	-0.052669	9.825152	0.045432	0.089665	-0.037038
+11.591042	0.014364	-0.026334	9.808394	0.046764	0.090464	-0.034907
+11.592099	-0.021546	-0.021546	9.851487	0.047164	0.086600	-0.035040
+11.593104	0.014364	-0.004788	9.858669	0.046364	0.087933	-0.034374
+11.594066	0.009576	-0.050275	9.889792	0.047031	0.088732	-0.036239
+11.595083	-0.009576	-0.011970	9.813182	0.049029	0.088466	-0.036372
+11.596109	0.047881	-0.052669	9.798818	0.049296	0.088199	-0.034907
+11.597102	-0.004788	-0.045487	9.803606	0.046764	0.088732	-0.037038
+11.598104	-0.028729	-0.040699	9.765301	0.046631	0.088732	-0.041302
+11.599102	-0.016758	-0.011970	9.750937	0.046364	0.089931	-0.040236
+11.600100	0.009576	-0.040699	9.822758	0.046098	0.088066	-0.034507
+11.601104	0.009576	-0.019152	9.794030	0.046897	0.086600	-0.033841
+11.602036	0.016758	0.007182	9.837123	0.047164	0.088332	-0.035972
+11.603042	0.026334	-0.035911	9.772483	0.046098	0.088599	-0.037704
+11.604079	-0.031123	-0.033517	9.703056	0.042634	0.089931	-0.036772
+11.605036	-0.016758	-0.021546	9.794030	0.044233	0.090198	-0.035839
+11.606053	0.000000	-0.002394	9.794030	0.047830	0.089798	-0.035706
+11.607047	-0.071821	-0.019152	9.825152	0.049562	0.087799	-0.037571
+11.608051	0.043093	-0.014364	9.865851	0.047297	0.088998	-0.040502
+11.609052	-0.007182	0.011970	9.753331	0.047164	0.088199	-0.037305
+11.610052	0.000000	0.047881	9.717420	0.048363	0.087666	-0.034507
+11.611105	0.045487	-0.002394	9.803606	0.048763	0.089132	-0.037438
+11.612130	0.019152	0.004788	9.808394	0.046631	0.089665	-0.039969
+11.613106	0.031123	0.009576	9.789242	0.047430	0.089265	-0.035573
+11.614097	0.026334	0.019152	9.779666	0.046231	0.088998	-0.033841
+11.615028	0.033517	-0.035911	9.815576	0.046098	0.089665	-0.033974
+11.616061	0.019152	-0.059851	9.849093	0.047164	0.088865	-0.035839
+11.617126	0.043093	-0.019152	9.861063	0.047697	0.086600	-0.032508
+11.618106	-0.002394	-0.019152	9.834729	0.047963	0.086867	-0.033041
+11.619044	0.019152	-0.004788	9.904156	0.048629	0.088998	-0.035972
+11.620103	-0.009576	0.000000	9.851487	0.048629	0.086600	-0.035173
+11.621102	-0.028729	-0.011970	9.791636	0.048230	0.090198	-0.033574
+11.622104	-0.019152	0.016758	9.820364	0.047031	0.090064	-0.034107
+11.623103	-0.040699	0.002394	9.746149	0.049029	0.089265	-0.033041
+11.624103	0.052669	-0.011970	9.755725	0.050628	0.089132	-0.037438
+11.625106	-0.007182	0.009576	9.813182	0.049429	0.088199	-0.038770
+11.626059	0.021546	-0.043093	9.827546	0.048363	0.089132	-0.039436
+11.627122	0.028729	-0.028729	9.777271	0.046364	0.089531	-0.035040
+11.628103	0.021546	-0.016758	9.784454	0.047031	0.087799	-0.035040
+11.629101	0.045487	0.019152	9.849093	0.046498	0.086734	-0.037305
+11.630105	0.086186	0.016758	9.789242	0.047031	0.088865	-0.036372
+11.631103	0.021546	-0.023940	9.743755	0.046364	0.091930	-0.033708
+11.632103	-0.023940	0.043093	9.791636	0.046364	0.092329	-0.039170
+11.633103	0.067033	0.000000	9.801212	0.047830	0.090331	-0.041035
+11.634104	0.083792	-0.023940	9.767695	0.050095	0.088199	-0.038770
+11.635080	0.026334	0.081397	9.832334	0.049162	0.086067	-0.037971
+11.636069	0.009576	-0.016758	9.755725	0.047164	0.085268	-0.039570
+11.637088	-0.016758	-0.016758	9.731785	0.044100	0.086334	-0.037838
+11.638105	-0.023940	0.028729	9.779666	0.044899	0.088998	-0.036372
+11.639105	0.023940	0.011970	9.834729	0.042501	0.089398	-0.036372
+11.640104	0.009576	-0.038305	9.856275	0.043700	0.088199	-0.035706
+11.641095	0.000000	0.028729	9.822758	0.045299	0.089132	-0.037838
+11.642091	-0.055063	0.035911	9.806000	0.047164	0.087266	-0.035839
+11.643104	-0.081397	0.059851	9.703056	0.048230	0.085135	-0.036639
+11.644105	-0.057457	0.007182	9.738967	0.046897	0.088199	-0.038104
+11.645103	-0.002394	-0.031123	9.853881	0.048763	0.089531	-0.035972
+11.646060	-0.011970	-0.007182	9.856275	0.046498	0.087266	-0.036905
+11.647089	0.035911	0.064639	9.817970	0.046764	0.088332	-0.039170
+11.648099	0.021546	0.014364	9.841911	0.046897	0.088466	-0.036905
+11.649104	0.007182	-0.004788	9.774877	0.047297	0.086867	-0.037971
+11.650101	0.033517	0.028729	9.841911	0.048096	0.087400	-0.036905
+11.651083	-0.019152	-0.011970	9.870639	0.046364	0.087533	-0.031176
+11.652035	-0.026334	-0.031123	9.803606	0.045832	0.086201	-0.033974
+11.653077	0.000000	-0.021546	9.849093	0.045565	0.086467	-0.036239
+11.654109	-0.021546	-0.040699	9.765301	0.046764	0.085401	-0.038371
+11.655106	-0.023940	0.055063	9.686298	0.048096	0.086734	-0.036239
+11.656107	-0.031123	0.014364	9.786848	0.047830	0.086067	-0.035972
+11.657054	-0.021546	0.047881	9.794030	0.048496	0.088732	-0.035440
+11.658125	0.052669	0.057457	9.762907	0.049429	0.087533	-0.036905
+11.659105	0.062245	0.021546	9.786848	0.050228	0.088066	-0.036639
+11.660063	0.016758	-0.033517	9.782060	0.048496	0.087533	-0.034374
+11.661052	-0.023940	-0.035911	9.782060	0.045832	0.086067	-0.034640
+11.662099	-0.055063	0.019152	9.765301	0.045565	0.088732	-0.036639
+11.663101	0.021546	0.019152	9.796424	0.048230	0.090864	-0.037838
+11.664061	0.016758	-0.028729	9.784454	0.048896	0.089398	-0.035440
+11.665035	-0.009576	0.023940	9.762907	0.047430	0.088332	-0.034374
+11.666106	-0.035911	0.021546	9.731785	0.045565	0.089398	-0.034374
+11.667095	-0.069427	-0.009576	9.820364	0.046364	0.086334	-0.035440
+11.668030	0.009576	0.014364	9.832334	0.048896	0.085135	-0.038504
+11.669102	0.016758	-0.011970	9.827546	0.049296	0.086867	-0.034374
+11.670056	0.023940	-0.031123	9.827546	0.049296	0.088998	-0.034507
+11.671052	-0.007182	-0.026334	9.794030	0.048363	0.088332	-0.034773
+11.672052	0.000000	0.007182	9.839517	0.047430	0.086867	-0.035573
+11.673053	0.047881	-0.016758	9.765301	0.047830	0.085668	-0.035972
+11.674103	0.035911	-0.028729	9.746149	0.045032	0.085934	-0.037172
+11.675102	0.021546	0.016758	9.760513	0.044100	0.088599	-0.038371
+11.676102	-0.014364	-0.023940	9.839517	0.046764	0.087799	-0.036106
+11.677102	-0.023940	0.007182	9.870639	0.049429	0.089265	-0.032775
+11.678086	-0.011970	0.009576	9.806000	0.047430	0.088066	-0.037038
+11.679118	0.055063	-0.004788	9.782060	0.044766	0.088599	-0.036239
+11.680102	-0.023940	-0.050275	9.870639	0.044233	0.089398	-0.036639
+11.681103	0.016758	-0.040699	9.825152	0.047697	0.086467	-0.040502
+11.682106	0.019152	-0.011970	9.810788	0.045965	0.086334	-0.036639
+11.683103	0.028729	-0.079003	9.868245	0.045698	0.086201	-0.035972
+11.684104	0.011970	-0.043093	9.777271	0.046631	0.085668	-0.035839
+11.685098	0.009576	-0.033517	9.784454	0.047430	0.088599	-0.037571
+11.686104	-0.004788	0.043093	9.724603	0.048230	0.088599	-0.038371
+11.687096	0.028729	0.004788	9.798818	0.046764	0.086734	-0.038770
+11.688098	-0.007182	-0.062245	9.849093	0.043700	0.086201	-0.039170
+11.689006	0.004788	-0.009576	9.734179	0.043433	0.085401	-0.039037
+11.690057	0.038305	0.021546	9.734179	0.045965	0.085401	-0.034240
+11.691051	0.035911	0.002394	9.791636	0.048096	0.085268	-0.035706
+11.692101	0.019152	-0.038305	9.750937	0.045432	0.090064	-0.037172
+11.693102	0.004788	-0.059851	9.755725	0.046498	0.090997	-0.038904
+11.694045	0.028729	-0.004788	9.779666	0.046498	0.088332	-0.038504
+11.695103	0.014364	-0.028729	9.796424	0.044632	0.087933	-0.037704
+11.696104	-0.031123	-0.040699	9.913732	0.045165	0.087266	-0.035173
+11.697099	0.038305	-0.026334	9.887397	0.045032	0.086467	-0.033175
+11.698102	0.055063	-0.002394	9.736573	0.045832	0.088599	-0.033041
+11.699082	0.047881	-0.007182	9.743755	0.046764	0.091397	-0.036905
+11.700054	0.045487	0.019152	9.762907	0.046098	0.088199	-0.037305
+11.701103	0.040699	0.014364	9.767695	0.046764	0.085401	-0.035573
+11.702062	0.000000	-0.009576	9.822758	0.047830	0.087133	-0.035306
+11.703020	0.009576	0.057457	9.837123	0.048363	0.087133	-0.035573
+11.704052	0.023940	0.062245	9.825152	0.047697	0.086734	-0.033974
+11.705111	0.004788	0.023940	9.832334	0.048230	0.087799	-0.033841
+11.706104	-0.004788	-0.023940	9.870639	0.047830	0.088732	-0.039969
+11.707102	0.052669	-0.009576	9.839517	0.046631	0.087400	-0.038371
+11.708102	0.000000	-0.035911	9.803606	0.045565	0.086201	-0.033974
+11.709036	0.019152	-0.009576	9.796424	0.046631	0.086734	-0.032508
+11.710127	0.050275	-0.021546	9.726997	0.051560	0.089931	-0.037172
+11.711102	0.023940	-0.035911	9.729391	0.050228	0.089798	-0.039037
+11.712102	0.043093	0.007182	9.765301	0.046498	0.090064	-0.035040
+11.713105	0.033517	-0.019152	9.868245	0.045032	0.088466	-0.034240
+11.714099	-0.047881	-0.057457	9.908944	0.046098	0.088865	-0.032375
+11.715102	-0.028729	-0.021546	9.861063	0.048096	0.090464	-0.034907
+11.716101	0.011970	0.019152	9.765301	0.048096	0.089798	-0.038504
+11.717103	0.002394	-0.033517	9.794030	0.047031	0.088332	-0.035440
+11.718063	0.021546	-0.047881	9.762907	0.047164	0.086201	-0.034507
+11.719060	0.002394	-0.057457	9.743755	0.049429	0.087000	-0.034107
+11.720038	-0.002394	-0.009576	9.796424	0.045698	0.090464	-0.035040
+11.721103	-0.014364	-0.021546	9.782060	0.046098	0.089398	-0.035706
+11.722103	-0.011970	-0.014364	9.789242	0.045165	0.087666	-0.036639
+11.723103	-0.052669	0.014364	9.815576	0.043966	0.089265	-0.036772
+11.724101	0.021546	0.021546	9.839517	0.046631	0.089665	-0.036905
+11.725100	0.002394	-0.021546	9.810788	0.046631	0.090331	-0.033708
+11.726087	-0.026334	-0.064639	9.719814	0.045432	0.086467	-0.036372
+11.727101	0.031123	-0.011970	9.794030	0.045965	0.086334	-0.037305
+11.728102	0.043093	-0.004788	9.813182	0.045432	0.085801	-0.038637
+11.729056	0.071821	-0.031123	9.810788	0.045032	0.083270	-0.038104
+11.730058	0.007182	-0.033517	9.794030	0.043300	0.084602	-0.038371
+11.731103	-0.052669	0.004788	9.784454	0.044899	0.087799	-0.037305
+11.732103	-0.007182	0.009576	9.801212	0.045698	0.090064	-0.037971
+11.733103	0.031123	0.011970	9.810788	0.045565	0.089931	-0.038637
+11.734103	-0.019152	-0.031123	9.679116	0.047031	0.088998	-0.037971
+11.735101	-0.004788	-0.009576	9.770089	0.047564	0.087266	-0.035040
+11.736100	-0.004788	0.028729	9.810788	0.049296	0.088332	-0.034507
+11.737102	0.002394	-0.004788	9.794030	0.049296	0.087400	-0.035972
+11.738054	-0.021546	-0.057457	9.813182	0.046897	0.085668	-0.040502
+11.739064	-0.023940	-0.074215	9.762907	0.045832	0.084735	-0.036772
+11.740038	0.016758	-0.021546	9.784454	0.046631	0.087666	-0.031842
+11.741121	0.026334	-0.004788	9.794030	0.046764	0.086867	-0.033308
+11.742095	0.016758	0.009576	9.779666	0.045565	0.085534	-0.036772
+11.743162	-0.004788	0.019152	9.851487	0.043567	0.087266	-0.035306
+11.744161	0.004788	0.059851	9.803606	0.044899	0.089665	-0.033708
+11.745163	-0.028729	0.043093	9.796424	0.046897	0.090730	-0.037704
+11.746165	0.014364	0.033517	9.772483	0.045965	0.088066	-0.037704
+11.747113	0.000000	0.021546	9.734179	0.044632	0.084868	-0.035306
+11.748162	0.047881	-0.031123	9.789242	0.045032	0.086201	-0.033175
+11.749117	0.002394	-0.019152	9.784454	0.047697	0.088332	-0.035306
+11.750071	-0.038305	-0.021546	9.849093	0.046631	0.088199	-0.037038
+11.751163	-0.021546	-0.023940	9.815576	0.045965	0.087533	-0.037038
+11.752105	0.007182	-0.026334	9.719814	0.048230	0.089132	-0.038904
+11.753101	0.009576	-0.038305	9.789242	0.048629	0.086467	-0.036239
+11.754095	0.031123	-0.069427	9.784454	0.049562	0.087666	-0.037038
+11.755096	0.031123	-0.023940	9.753331	0.045832	0.088199	-0.037438
+11.756161	0.007182	-0.033517	9.803606	0.046098	0.089531	-0.035440
+11.757123	-0.062245	-0.004788	9.841911	0.047164	0.089398	-0.038104
+11.758165	-0.059851	-0.031123	9.770089	0.047963	0.088332	-0.038237
+11.759099	-0.004788	-0.086186	9.777271	0.046631	0.087133	-0.039303
+11.760118	0.021546	-0.021546	9.803606	0.047963	0.088066	-0.038637
+11.761158	-0.007182	0.031123	9.868245	0.049296	0.087000	-0.035839
+11.762164	-0.014364	0.035911	9.873033	0.048629	0.088998	-0.035839
+11.763100	0.011970	0.028729	9.858669	0.050095	0.089931	-0.038637
+11.764160	-0.007182	0.000000	9.810788	0.048496	0.087000	-0.039436
+11.765114	-0.014364	0.011970	9.798818	0.046897	0.086867	-0.038504
+11.766162	0.021546	0.059851	9.863457	0.045299	0.087799	-0.037438
+11.767159	-0.031123	0.002394	9.784454	0.043833	0.087933	-0.034240
+11.768118	0.021546	0.014364	9.753331	0.044899	0.085268	-0.036106
+11.769115	0.040699	0.011970	9.786848	0.045698	0.086734	-0.037571
+11.770108	0.043093	0.019152	9.858669	0.047164	0.089531	-0.037704
+11.771160	0.045487	-0.038305	9.899368	0.046631	0.088998	-0.037838
+11.772161	0.052669	-0.026334	9.849093	0.045165	0.087000	-0.035706
+11.773161	0.023940	0.028729	9.743755	0.044766	0.086734	-0.035440
+11.774162	0.038305	0.059851	9.698268	0.043966	0.087000	-0.037038
+11.775160	0.023940	0.055063	9.762907	0.045299	0.090730	-0.041168
+11.776159	0.016758	-0.016758	9.801212	0.045165	0.089798	-0.039170
+11.777114	-0.023940	-0.019152	9.798818	0.046631	0.087133	-0.037438
+11.778155	0.004788	-0.019152	9.755725	0.047430	0.085002	-0.037838
+11.779160	0.050275	-0.035911	9.736573	0.045565	0.086067	-0.036505
+11.780161	0.071821	-0.047881	9.679116	0.044899	0.087933	-0.033308
+11.781160	0.038305	-0.026334	9.801212	0.048230	0.089132	-0.035839
+11.782167	0.009576	-0.007182	9.841911	0.049029	0.089398	-0.038237
+11.783159	-0.007182	0.019152	9.849093	0.047697	0.090064	-0.033974
+11.784162	-0.023940	0.016758	9.877821	0.045698	0.088332	-0.036505
+11.785118	-0.038305	0.033517	9.820364	0.045565	0.086600	-0.035839
+11.786118	0.000000	0.016758	9.849093	0.045432	0.086867	-0.035839
+11.787158	0.033517	-0.009576	9.806000	0.046631	0.086467	-0.036772
+11.788158	0.007182	-0.043093	9.820364	0.048096	0.086334	-0.037838
+11.789160	0.023940	-0.011970	9.767695	0.047164	0.085668	-0.035440
+11.790106	0.117308	-0.004788	9.770089	0.045432	0.084735	-0.033308
+11.791157	0.055063	0.000000	9.743755	0.046098	0.086734	-0.033574
+11.792098	0.011970	-0.050275	9.784454	0.047031	0.086334	-0.035440
+11.793157	0.035911	-0.074215	9.806000	0.048763	0.085801	-0.036372
+11.794090	0.004788	-0.016758	9.806000	0.045965	0.088332	-0.034507
+11.795160	0.038305	-0.064639	9.832334	0.045432	0.088865	-0.031443
+11.796091	0.067033	-0.071821	9.786848	0.048096	0.088066	-0.033841
+11.797127	0.026334	-0.026334	9.839517	0.049962	0.086734	-0.037571
+11.798115	0.000000	-0.050275	9.810788	0.047430	0.086867	-0.038637
+11.799092	-0.021546	-0.076609	9.817970	0.044366	0.087400	-0.036106
+11.800065	0.023940	-0.050275	9.803606	0.044899	0.085268	-0.034374
+11.801089	0.023940	-0.009576	9.825152	0.045832	0.085135	-0.034640
+11.802091	-0.014364	-0.004788	9.806000	0.048230	0.087799	-0.037038
+11.803090	-0.004788	-0.009576	9.817970	0.048230	0.089265	-0.035839
+11.804090	0.004788	0.007182	9.796424	0.046764	0.089931	-0.034773
+11.805095	0.002394	-0.045487	9.729391	0.046098	0.089265	-0.034107
+11.806078	0.043093	0.004788	9.736573	0.046631	0.088199	-0.036639
+11.807073	0.062245	-0.007182	9.719814	0.047564	0.087000	-0.036772
+11.808090	0.071821	-0.004788	9.839517	0.046631	0.087133	-0.035440
+11.809157	0.047881	-0.023940	9.837123	0.044899	0.085934	-0.037838
+11.810111	0.035911	-0.007182	9.803606	0.046098	0.088066	-0.035706
+11.811094	0.019152	0.007182	9.803606	0.049828	0.088466	-0.034374
+11.812073	0.033517	0.004788	9.844305	0.047564	0.089531	-0.036639
+11.813096	0.023940	-0.033517	9.863457	0.046498	0.089798	-0.035306
+11.814083	0.052669	-0.004788	9.755725	0.047430	0.090864	-0.034107
+11.815094	0.033517	-0.028729	9.758119	0.044899	0.088599	-0.034107
+11.816161	0.035911	-0.014364	9.738967	0.046098	0.084602	-0.032908
+11.817079	0.040699	-0.002394	9.861063	0.050228	0.085801	-0.036106
+11.818114	0.000000	-0.016758	9.853881	0.049562	0.087266	-0.038504
+11.819106	-0.016758	-0.007182	9.782060	0.047564	0.087666	-0.039170
+11.820090	-0.004788	0.026334	9.796424	0.044100	0.087400	-0.036505
+11.821159	0.011970	0.031123	9.801212	0.045432	0.089931	-0.035306
+11.822166	0.031123	-0.009576	9.765301	0.047164	0.087799	-0.036772
+11.823159	0.021546	0.014364	9.803606	0.047963	0.085668	-0.035573
+11.824162	0.028729	-0.033517	9.834729	0.045832	0.085135	-0.036505
+11.825160	0.021546	-0.028729	9.901762	0.044499	0.084202	-0.037704
+11.826133	0.035911	-0.004788	9.875427	0.047297	0.088332	-0.037571
+11.827115	0.028729	0.028729	9.853881	0.047297	0.088998	-0.036772
+11.828158	0.016758	0.004788	9.755725	0.047164	0.090464	-0.034907
+11.829161	-0.007182	0.000000	9.782060	0.046764	0.090464	-0.038504
+11.830163	0.026334	-0.023940	9.808394	0.046631	0.087000	-0.039836
+11.831160	0.028729	-0.002394	9.825152	0.043567	0.086067	-0.039303
+11.832160	0.055063	0.002394	9.789242	0.045032	0.084868	-0.036505
+11.833165	-0.014364	0.007182	9.695874	0.047697	0.086867	-0.036372
+11.834139	0.023940	0.064639	9.707844	0.046897	0.087533	-0.036905
+11.835111	0.023940	-0.004788	9.760513	0.047430	0.087400	-0.037704
+11.836116	-0.031123	0.007182	9.736573	0.046764	0.086201	-0.036639
+11.837097	-0.002394	0.004788	9.743755	0.046364	0.085002	-0.036905
+11.838081	0.000000	0.011970	9.760513	0.046231	0.084069	-0.035173
+11.839133	0.035911	-0.043093	9.841911	0.044233	0.086067	-0.034240
+11.840115	-0.007182	0.009576	9.796424	0.045832	0.088732	-0.034507
+11.841163	0.011970	0.014364	9.782060	0.047164	0.088732	-0.037172
+11.842125	0.067033	-0.021546	9.741361	0.048363	0.087799	-0.036772
+11.843113	0.040699	0.016758	9.762907	0.044366	0.087799	-0.034374
+11.844158	0.043093	-0.021546	9.767695	0.044100	0.087266	-0.035972
+11.845160	-0.026334	-0.026334	9.748543	0.048363	0.087933	-0.035972
+11.846095	-0.004788	-0.019152	9.693480	0.048363	0.090064	-0.037172
+11.847116	0.021546	0.016758	9.796424	0.049029	0.089665	-0.040236
+11.848159	0.002394	0.023940	9.717420	0.048496	0.087933	-0.040369
+11.849083	-0.021546	-0.021546	9.779666	0.048629	0.087133	-0.036239
+11.850154	-0.035911	0.000000	9.791636	0.047164	0.088599	-0.033708
+11.851089	0.019152	-0.007182	9.710238	0.045032	0.086734	-0.032908
+11.852117	-0.004788	0.021546	9.746149	0.045698	0.087400	-0.037038
+11.853162	-0.059851	0.031123	9.746149	0.048629	0.088066	-0.036239
+11.854091	-0.011970	-0.011970	9.777271	0.047830	0.088332	-0.034374
+11.855162	0.009576	-0.028729	9.889792	0.047697	0.089265	-0.037038
+11.856117	0.035911	0.000000	9.841911	0.047031	0.089798	-0.038637
+11.857105	0.040699	0.007182	9.786848	0.045965	0.090198	-0.039703
+11.858164	0.059851	-0.040699	9.803606	0.048096	0.089531	-0.038504
+11.859159	0.023940	-0.057457	9.762907	0.047564	0.088066	-0.035706
+11.860104	-0.043093	0.002394	9.738967	0.048230	0.087533	-0.034640
+11.861074	-0.019152	-0.069427	9.822758	0.046631	0.087400	-0.039436
+11.862076	0.000000	0.000000	9.784454	0.047564	0.089398	-0.037704
+11.863153	0.038305	0.002394	9.774877	0.049296	0.088466	-0.034374
+11.864103	0.019152	-0.023940	9.722208	0.047564	0.087933	-0.032375
+11.865112	-0.038305	-0.007182	9.707844	0.046498	0.088066	-0.034773
+11.866146	-0.004788	0.028729	9.815576	0.046897	0.088199	-0.033841
+11.867158	0.038305	-0.040699	9.810788	0.048096	0.087799	-0.036772
+11.868119	-0.007182	-0.055063	9.803606	0.047697	0.087133	-0.037438
+11.869159	0.019152	-0.059851	9.779666	0.047697	0.088998	-0.035040
+11.870083	0.045487	-0.019152	9.796424	0.049029	0.087266	-0.033574
+11.871159	0.023940	0.004788	9.856275	0.047164	0.085801	-0.033308
+11.872159	-0.016758	-0.040699	9.803606	0.045965	0.086067	-0.036639
+11.873162	-0.026334	-0.021546	9.736573	0.048096	0.087000	-0.038637
+11.874116	-0.009576	-0.031123	9.791636	0.047564	0.088865	-0.038104
+11.875153	-0.038305	-0.009576	9.849093	0.047164	0.088332	-0.037704
+11.876158	-0.038305	-0.043093	9.808394	0.044766	0.087133	-0.035706
+11.877159	0.031123	-0.011970	9.772483	0.047564	0.087533	-0.035173
+11.878163	0.052669	-0.019152	9.753331	0.047963	0.088466	-0.034374
+11.879157	0.052669	0.038305	9.832334	0.046631	0.089265	-0.035972
+11.880157	0.055063	0.023940	9.767695	0.046098	0.089398	-0.038770
+11.881126	0.062245	0.011970	9.731785	0.049162	0.086467	-0.040902
+11.882162	0.028729	0.047881	9.794030	0.050761	0.087000	-0.040636
+11.883111	0.035911	0.043093	9.798818	0.046231	0.084735	-0.036106
+11.884139	0.038305	0.028729	9.731785	0.046631	0.085534	-0.035173
+11.885158	0.045487	-0.019152	9.784454	0.047297	0.087933	-0.036106
+11.886162	0.026334	0.019152	9.789242	0.046631	0.090331	-0.038104
+11.887095	0.004788	0.028729	9.820364	0.045432	0.087799	-0.036505
+11.888080	0.021546	-0.016758	9.808394	0.046364	0.086467	-0.035573
+11.889076	0.052669	0.000000	9.791636	0.048230	0.086467	-0.034907
+11.890110	0.009576	-0.007182	9.779666	0.047830	0.088332	-0.036106
+11.891160	0.059851	0.057457	9.688692	0.046764	0.088466	-0.035706
+11.892101	0.004788	0.057457	9.877821	0.045165	0.088998	-0.035706
+11.893089	-0.007182	-0.007182	9.875427	0.044766	0.086201	-0.037038
+11.894159	0.002394	-0.021546	9.789242	0.046498	0.089798	-0.036239
+11.895115	0.057457	-0.007182	9.801212	0.048230	0.088332	-0.035839
+11.896161	0.035911	-0.040699	9.846699	0.048629	0.085934	-0.039836
+11.897100	0.026334	-0.014364	9.822758	0.047963	0.087266	-0.038371
+11.898092	0.028729	0.014364	9.760513	0.046631	0.087933	-0.033708
+11.899127	0.033517	-0.002394	9.794030	0.046764	0.087266	-0.035173
+11.900159	0.028729	-0.016758	9.813182	0.046764	0.086734	-0.039836
+11.901075	0.071821	-0.047881	9.734179	0.046498	0.085934	-0.038504
+11.902104	0.033517	0.014364	9.770089	0.047430	0.089398	-0.035706
+11.903124	-0.047881	-0.009576	9.825152	0.045698	0.089398	-0.035173
+11.904159	-0.045487	-0.021546	9.820364	0.046098	0.086334	-0.037038
+11.905112	0.004788	-0.052669	9.798818	0.048629	0.086067	-0.037971
+11.906163	0.062245	0.038305	9.798818	0.049562	0.086067	-0.036639
+11.907111	0.019152	-0.026334	9.777271	0.046098	0.085668	-0.036639
+11.908161	0.023940	-0.052669	9.794030	0.044632	0.085534	-0.034907
+11.909160	0.021546	-0.057457	9.798818	0.047697	0.086600	-0.035440
+11.910111	0.043093	-0.007182	9.772483	0.051294	0.086734	-0.035040
+11.911113	0.062245	0.023940	9.743755	0.051827	0.088732	-0.035306
+11.912152	-0.004788	0.014364	9.774877	0.050095	0.088199	-0.032642
+11.913160	0.002394	0.023940	9.755725	0.047297	0.086734	-0.032109
+11.914098	0.028729	0.007182	9.794030	0.045965	0.085401	-0.035440
+11.915159	-0.009576	0.014364	9.858669	0.047564	0.083403	-0.036505
+11.916162	-0.002394	0.035911	9.892186	0.047564	0.087000	-0.036239
+11.917106	0.033517	0.062245	9.820364	0.046897	0.088599	-0.036905
+11.918099	0.016758	0.021546	9.820364	0.047031	0.088066	-0.035573
+11.919087	-0.004788	-0.016758	9.825152	0.045299	0.088066	-0.034773
+11.920067	0.021546	-0.004788	9.853881	0.045299	0.088466	-0.034107
+11.921060	0.038305	-0.043093	9.925702	0.047564	0.090198	-0.038637
+11.922045	0.043093	-0.002394	9.894580	0.045432	0.090730	-0.039303
+11.923040	-0.033517	-0.014364	9.875427	0.045832	0.088332	-0.035839
+11.924045	-0.004788	0.007182	9.827546	0.047297	0.087799	-0.037305
+11.925051	0.050275	0.023940	9.746149	0.047830	0.087933	-0.039037
+11.926077	0.026334	0.000000	9.806000	0.048230	0.088466	-0.041835
+11.927159	-0.031123	0.011970	9.786848	0.048230	0.086867	-0.037305
+11.928159	0.057457	-0.033517	9.758119	0.047963	0.087133	-0.035839
+11.929083	-0.023940	-0.007182	9.841911	0.048629	0.088732	-0.035440
+11.930110	-0.086186	-0.004788	9.913732	0.047430	0.088732	-0.037971
+11.931084	0.007182	-0.019152	9.882609	0.045965	0.088732	-0.043300
+11.932131	0.021546	-0.028729	9.820364	0.045698	0.085934	-0.038104
+11.933157	-0.026334	-0.043093	9.779666	0.046231	0.084868	-0.033175
+11.934164	-0.026334	-0.047881	9.844305	0.045698	0.086734	-0.037172
+11.935090	0.000000	-0.007182	9.815576	0.046098	0.088199	-0.038504
+11.936160	0.011970	0.035911	9.839517	0.046764	0.088599	-0.037571
+11.937163	0.009576	0.014364	9.908944	0.046897	0.088066	-0.037172
+11.938165	0.021546	0.021546	9.856275	0.048763	0.090730	-0.040103
+11.939121	0.009576	0.000000	9.738967	0.047697	0.088466	-0.039303
+11.940116	-0.002394	-0.031123	9.801212	0.043966	0.086600	-0.038371
+11.941105	0.062245	-0.062245	9.803606	0.043833	0.087133	-0.035440
+11.942169	0.074215	0.059851	9.774877	0.047297	0.087933	-0.037438
+11.943071	-0.007182	0.028729	9.791636	0.047963	0.089265	-0.038504
+11.944159	-0.031123	-0.023940	9.808394	0.045965	0.087133	-0.039836
+11.945162	0.011970	-0.026334	9.765301	0.046098	0.088732	-0.037838
+11.946162	0.016758	-0.004788	9.870639	0.046764	0.090198	-0.036772
+11.947162	0.021546	-0.045487	9.892186	0.046764	0.089398	-0.037172
+11.948104	0.023940	-0.038305	9.746149	0.049962	0.088599	-0.035573
+11.949102	-0.016758	-0.002394	9.806000	0.048896	0.087533	-0.036106
+11.950159	-0.050275	-0.045487	9.870639	0.046231	0.085801	-0.032242
+11.951102	0.076609	-0.076609	9.837123	0.043966	0.086467	-0.034107
+11.952104	0.033517	-0.002394	9.765301	0.044233	0.085401	-0.036106
+11.953163	0.033517	-0.014364	9.755725	0.045698	0.083802	-0.037438
+11.954164	0.007182	0.028729	9.758119	0.047430	0.086600	-0.035173
+11.955159	-0.028729	0.002394	9.837123	0.046231	0.089665	-0.034773
+11.956161	0.011970	0.055063	9.937672	0.046231	0.089265	-0.037438
+11.957125	0.040699	0.007182	9.844305	0.044899	0.088599	-0.037038
+11.958101	0.055063	0.002394	9.789242	0.046498	0.086734	-0.035440
+11.959164	-0.007182	-0.028729	9.777271	0.047031	0.087400	-0.036505
+11.960106	-0.047881	0.004788	9.777271	0.046231	0.086600	-0.036239
+11.961168	-0.019152	0.004788	9.719814	0.047830	0.087799	-0.034640
+11.962163	0.007182	0.021546	9.786848	0.043966	0.088732	-0.035573
+11.963159	0.038305	0.028729	9.779666	0.043300	0.087799	-0.037838
+11.964158	0.040699	-0.016758	9.820364	0.046498	0.087933	-0.037172
+11.965102	-0.014364	-0.011970	9.767695	0.049695	0.088332	-0.035972
+11.966079	0.016758	-0.040699	9.786848	0.049029	0.087133	-0.036772
+11.967157	0.007182	-0.016758	9.798818	0.047430	0.089132	-0.038904
+11.968106	0.028729	0.050275	9.839517	0.046764	0.089398	-0.036106
+11.969162	0.002394	0.043093	9.846699	0.046631	0.087000	-0.034640
+11.970104	-0.014364	0.000000	9.767695	0.048496	0.086201	-0.035573
+11.971159	0.021546	-0.019152	9.746149	0.050761	0.085801	-0.034507
+11.972162	-0.009576	-0.038305	9.772483	0.046364	0.087933	-0.033041
+11.973163	-0.016758	-0.009576	9.705450	0.046764	0.087666	-0.035573
+11.974118	0.002394	-0.007182	9.827546	0.047430	0.086067	-0.034640
+11.975123	-0.021546	-0.014364	9.820364	0.048496	0.086600	-0.036505
+11.976162	0.023940	0.021546	9.722208	0.049695	0.088066	-0.039969
+11.977160	0.021546	0.009576	9.734179	0.050228	0.087000	-0.037704
+11.978162	-0.035911	0.033517	9.841911	0.049029	0.087933	-0.037571
+11.979099	-0.023940	0.000000	9.899368	0.045698	0.090064	-0.036505
+11.980090	-0.047881	0.055063	9.954431	0.045432	0.091930	-0.038637
+11.981149	0.009576	0.052669	9.923308	0.047297	0.088998	-0.036239
+11.982162	0.009576	0.033517	9.873033	0.047697	0.088998	-0.035040
+11.983112	-0.014364	-0.040699	9.808394	0.047430	0.089531	-0.032508
+11.984150	0.004788	-0.040699	9.834729	0.047297	0.089132	-0.035440
+11.985164	0.038305	-0.086186	9.863457	0.046364	0.087533	-0.041835
+11.986163	0.002394	-0.098156	9.817970	0.045032	0.088865	-0.037704
+11.987118	0.019152	-0.014364	9.822758	0.047697	0.088066	-0.037038
+11.988081	0.050275	0.038305	9.841911	0.047697	0.088865	-0.038104
+11.989081	0.004788	-0.023940	9.825152	0.045299	0.086734	-0.036106
+11.990083	0.023940	-0.100550	9.882609	0.046897	0.085534	-0.033574
+11.991159	0.002394	-0.026334	9.877821	0.048896	0.086734	-0.034374
+11.992076	0.004788	-0.011970	9.803606	0.048096	0.087799	-0.036239
+11.993211	0.004788	-0.074215	9.844305	0.045432	0.087933	-0.037704
+11.994161	-0.031123	-0.081397	9.841911	0.046498	0.087266	-0.038104
+11.995161	-0.026334	0.000000	9.837123	0.047164	0.087000	-0.037838
+11.996160	0.033517	0.011970	9.746149	0.046764	0.088332	-0.038104
+11.997161	0.000000	0.011970	9.760513	0.046631	0.087533	-0.038770
+11.998163	0.000000	0.040699	9.724603	0.046364	0.088599	-0.038104
+11.999122	0.009576	-0.021546	9.762907	0.045965	0.088466	-0.034240
+12.000162	-0.038305	-0.038305	9.760513	0.046098	0.088599	-0.033441
+12.001104	-0.009576	0.035911	9.750937	0.046231	0.088599	-0.038104
+12.002080	0.011970	0.026334	9.738967	0.045832	0.087933	-0.037571
+12.003158	-0.035911	0.043093	9.762907	0.045165	0.087000	-0.035306
+12.004157	-0.011970	0.007182	9.789242	0.045032	0.087400	-0.033841
+12.005159	-0.023940	-0.019152	9.772483	0.048496	0.085801	-0.034907
+12.006162	0.004788	0.038305	9.789242	0.048629	0.086734	-0.035839
+12.007114	-0.043093	0.004788	9.861063	0.048629	0.090198	-0.034507
+12.008158	-0.033517	-0.031123	9.889792	0.050894	0.090597	-0.035573
+12.009157	-0.023940	0.002394	9.856275	0.046498	0.089665	-0.036106
+12.010078	-0.011970	-0.016758	9.741361	0.045432	0.086201	-0.036239
+12.011108	0.067033	0.021546	9.758119	0.045698	0.083403	-0.035839
+12.012153	0.033517	0.031123	9.827546	0.045432	0.084469	-0.035306
+12.013092	0.023940	-0.055063	9.839517	0.045965	0.087799	-0.031709
+12.014065	0.011970	-0.059851	9.837123	0.046364	0.090331	-0.035306
+12.015091	-0.016758	-0.011970	9.820364	0.047564	0.090064	-0.037038
+12.016156	0.007182	-0.023940	9.865851	0.047430	0.089798	-0.037971
+12.017160	0.002394	0.019152	9.841911	0.044366	0.090464	-0.040502
+12.018161	0.000000	-0.026334	9.731785	0.044233	0.090730	-0.037172
+12.019096	0.031123	-0.028729	9.762907	0.044766	0.084735	-0.037305
+12.020121	0.011970	0.021546	9.796424	0.044766	0.083136	-0.037838
+12.021071	-0.014364	0.047881	9.719814	0.048096	0.087400	-0.036505
+12.022162	-0.028729	-0.023940	9.755725	0.049162	0.091530	-0.037838
+12.023158	-0.021546	-0.043093	9.794030	0.048629	0.090064	-0.039303
+12.024156	-0.031123	-0.021546	9.801212	0.048496	0.088732	-0.038104
+12.025159	0.069427	-0.021546	9.834729	0.047963	0.088066	-0.036772
+12.026161	0.043093	-0.004788	9.865851	0.046364	0.088199	-0.037438
+12.027157	0.035911	0.021546	9.844305	0.049296	0.088599	-0.035440
+12.028158	-0.014364	0.021546	9.827546	0.049296	0.089931	-0.036106
+12.029114	-0.079003	0.000000	9.765301	0.047963	0.092063	-0.039703
+12.030157	-0.023940	-0.052669	9.815576	0.047430	0.089931	-0.040502
+12.031157	0.002394	-0.040699	9.813182	0.043700	0.088332	-0.036905
+12.032095	0.019152	-0.043093	9.808394	0.042767	0.088199	-0.036772
+12.033086	-0.009576	-0.007182	9.858669	0.046764	0.087666	-0.032642
+12.034050	0.019152	-0.011970	9.750937	0.046897	0.087533	-0.034773
+12.035054	0.009576	0.016758	9.806000	0.044766	0.087933	-0.038504
+12.036060	-0.009576	-0.023940	9.880215	0.046231	0.090198	-0.040103
+12.037063	0.016758	-0.004788	9.877821	0.046897	0.091263	-0.035173
+12.038096	0.028729	0.035911	9.875427	0.045432	0.090198	-0.037305
+12.039092	0.038305	0.021546	9.875427	0.043567	0.088466	-0.037172
+12.040086	0.014364	0.000000	9.841911	0.045698	0.086867	-0.037172
+12.041089	0.045487	0.002394	9.901762	0.046764	0.084868	-0.040502
+12.042095	0.040699	0.007182	9.849093	0.044766	0.083669	-0.040369
+12.043069	0.004788	-0.004788	9.794030	0.046364	0.084069	-0.035040
+12.044090	-0.043093	-0.093368	9.813182	0.046631	0.087799	-0.033308
+12.045099	-0.019152	-0.052669	9.851487	0.047031	0.087533	-0.032242
+12.046161	0.019152	-0.033517	9.770089	0.046631	0.087133	-0.033041
+12.047094	0.026334	-0.045487	9.798818	0.045832	0.087133	-0.034107
+12.048155	0.043093	0.011970	9.868245	0.046231	0.087533	-0.036106
+12.049160	0.023940	-0.011970	9.858669	0.046231	0.087400	-0.035440
+12.050111	-0.019152	0.002394	9.825152	0.045432	0.087933	-0.037438
+12.051100	-0.016758	-0.004788	9.813182	0.045698	0.086334	-0.038237
+12.052092	0.000000	-0.007182	9.786848	0.046098	0.085534	-0.035706
+12.053137	-0.002394	-0.023940	9.863457	0.047031	0.086734	-0.037838
+12.054159	0.000000	-0.043093	9.815576	0.046231	0.086334	-0.038904
+12.055159	0.040699	-0.019152	9.753331	0.046098	0.088998	-0.036772
+12.056110	0.019152	0.014364	9.810788	0.045165	0.089398	-0.037305
+12.057111	0.026334	0.043093	9.815576	0.046631	0.087666	-0.037571
+12.058087	0.038305	0.059851	9.782060	0.049296	0.086334	-0.036372
+12.059058	0.002394	-0.011970	9.813182	0.049695	0.088199	-0.036239
+12.060088	-0.007182	-0.021546	9.806000	0.047430	0.089265	-0.032775
+12.061111	0.007182	0.021546	9.829940	0.046498	0.088599	-0.037305
+12.062137	0.021546	-0.019152	9.770089	0.047564	0.087933	-0.040636
+12.063163	0.011970	0.019152	9.746149	0.048496	0.088732	-0.035573
+12.064156	-0.004788	-0.002394	9.837123	0.046364	0.088732	-0.034773
+12.065159	0.028729	-0.021546	9.846699	0.044366	0.088998	-0.035573
+12.066163	0.026334	-0.052669	9.858669	0.043966	0.089265	-0.036905
+12.067159	0.045487	-0.079003	9.880215	0.043966	0.087000	-0.034907
+12.068151	0.052669	0.009576	9.889792	0.045832	0.087533	-0.035839
+12.069161	-0.016758	-0.033517	9.837123	0.046631	0.087133	-0.036639
+12.070105	-0.040699	-0.021546	9.841911	0.046098	0.089265	-0.037838
+12.071110	-0.093368	-0.011970	9.813182	0.046498	0.089931	-0.037305
+12.072160	-0.043093	-0.016758	9.777271	0.045698	0.087400	-0.033841
+12.073157	0.028729	-0.035911	9.822758	0.047564	0.084602	-0.033841
+12.074159	0.009576	-0.028729	9.868245	0.048363	0.084335	-0.035306
+12.075158	0.011970	0.007182	9.700662	0.048096	0.086867	-0.039037
+12.076160	0.021546	-0.021546	9.715026	0.048496	0.085934	-0.034907
+12.077158	0.019152	0.019152	9.772483	0.049029	0.086467	-0.033441
+12.078162	0.028729	0.016758	9.849093	0.047564	0.088066	-0.034507
+12.079113	-0.021546	-0.009576	9.837123	0.045832	0.087533	-0.037571
+12.080095	0.043093	-0.002394	9.765301	0.047297	0.087133	-0.035972
+12.081164	0.038305	-0.016758	9.738967	0.047430	0.085668	-0.035306
+12.082165	0.016758	-0.067033	9.762907	0.046098	0.086600	-0.034240
+12.083156	-0.043093	-0.011970	9.820364	0.046631	0.088466	-0.033175
+12.084158	-0.026334	-0.038305	9.801212	0.047697	0.088599	-0.034107
+12.085159	0.009576	0.011970	9.774877	0.046897	0.088066	-0.034374
+12.086161	-0.009576	-0.059851	9.734179	0.046764	0.083802	-0.036772
+12.087158	0.052669	-0.007182	9.703056	0.045965	0.084469	-0.037438
+12.088111	0.038305	0.026334	9.829940	0.046364	0.088332	-0.036239
+12.089107	0.045487	0.021546	9.803606	0.049429	0.092063	-0.035839
+12.090141	0.035911	-0.009576	9.837123	0.049695	0.093662	-0.035706
+12.091160	-0.011970	0.031123	9.760513	0.047164	0.091796	-0.036239
+12.092157	0.002394	0.026334	9.841911	0.047164	0.090064	-0.038904
+12.093098	0.000000	-0.019152	9.817970	0.046098	0.085934	-0.037838
+12.094161	-0.009576	-0.019152	9.815576	0.045432	0.085268	-0.038504
+12.095119	0.043093	-0.019152	9.746149	0.045698	0.087400	-0.036905
+12.096156	0.009576	0.033517	9.765301	0.046098	0.086600	-0.035972
+12.097156	0.023940	0.007182	9.851487	0.045432	0.088466	-0.032775
+12.098113	-0.004788	-0.033517	9.820364	0.044766	0.087933	-0.032375
+12.099134	0.002394	-0.045487	9.758119	0.047031	0.083936	-0.035306
+12.100120	0.057457	0.007182	9.724603	0.046364	0.083936	-0.040236
+12.101156	0.031123	-0.004788	9.856275	0.044632	0.088466	-0.040769
+12.102108	-0.021546	-0.002394	9.832334	0.046498	0.090464	-0.036905
+12.103156	-0.002394	-0.059851	9.832334	0.046631	0.088865	-0.033175
+12.104156	0.028729	0.002394	9.832334	0.048763	0.085668	-0.032375
+12.105158	-0.004788	0.023940	9.786848	0.048230	0.085934	-0.034374
+12.106162	-0.019152	-0.011970	9.829940	0.045965	0.088599	-0.033308
+12.107111	-0.040699	0.021546	9.798818	0.043433	0.089265	-0.038371
+12.108133	0.014364	0.026334	9.798818	0.046098	0.088332	-0.038904
+12.109163	0.014364	-0.033517	9.765301	0.047031	0.087666	-0.036772
+12.110160	0.002394	-0.038305	9.753331	0.048230	0.088865	-0.034240
+12.111164	-0.007182	-0.031123	9.731785	0.046764	0.086734	-0.035173
+12.112156	0.043093	-0.040699	9.741361	0.048096	0.088599	-0.037571
+12.113157	-0.011970	-0.031123	9.765301	0.048496	0.088199	-0.035306
+12.114162	-0.014364	0.038305	9.839517	0.048763	0.087533	-0.037571
+12.115109	0.002394	0.093368	9.856275	0.046231	0.088066	-0.040502
+12.116111	-0.011970	0.047881	9.822758	0.047963	0.088865	-0.035306
+12.117119	0.062245	0.088580	9.796424	0.050095	0.087799	-0.031309
+12.118115	0.007182	-0.035911	9.731785	0.049029	0.086467	-0.035839
+12.119156	0.035911	-0.069427	9.760513	0.048763	0.085934	-0.038637
+12.120116	-0.021546	-0.045487	9.815576	0.048763	0.087533	-0.038504
+12.121156	0.026334	0.000000	9.801212	0.047430	0.088865	-0.038104
+12.122159	0.079003	-0.011970	9.834729	0.046897	0.088865	-0.036639
+12.123156	0.009576	-0.023940	9.892186	0.047697	0.085002	-0.035173
+12.124156	0.031123	-0.031123	9.846699	0.047297	0.083802	-0.036905
+12.125111	0.000000	-0.040699	9.789242	0.046897	0.087666	-0.034374
+12.126129	0.002394	-0.026334	9.741361	0.047564	0.089132	-0.032775
+12.127159	-0.011970	0.023940	9.803606	0.046897	0.088066	-0.033574
+12.128156	0.019152	-0.028729	9.834729	0.047297	0.090198	-0.036505
+12.129162	0.016758	-0.002394	9.820364	0.048096	0.090198	-0.036905
+12.130160	0.021546	-0.007182	9.726997	0.045698	0.088199	-0.039436
+12.131155	-0.002394	-0.004788	9.770089	0.046098	0.086334	-0.034907
+12.132156	-0.021546	0.043093	9.885003	0.046498	0.084069	-0.034640
+12.133156	-0.016758	0.009576	9.803606	0.048363	0.086334	-0.036905
+12.134115	-0.038305	0.014364	9.755725	0.048496	0.088332	-0.037571
+12.135113	-0.067033	-0.002394	9.746149	0.046764	0.089798	-0.037038
+12.136134	-0.009576	-0.023940	9.808394	0.045832	0.088599	-0.036639
+12.137157	0.000000	-0.014364	9.837123	0.046498	0.086067	-0.035706
+12.138160	0.031123	-0.002394	9.789242	0.049162	0.086600	-0.033974
+12.139157	0.035911	-0.033517	9.741361	0.049429	0.088466	-0.036905
+12.140171	0.052669	0.011970	9.729391	0.049296	0.088998	-0.036505
+12.141154	0.047881	-0.002394	9.868245	0.047430	0.089798	-0.040636
+12.142160	0.035911	0.014364	9.870639	0.045565	0.089798	-0.042101
+12.143091	0.045487	0.004788	9.791636	0.046631	0.089265	-0.039436
+12.144085	0.002394	0.014364	9.779666	0.047564	0.089531	-0.035306
+12.145132	-0.033517	-0.033517	9.832334	0.047164	0.092196	-0.034640
+12.146167	-0.016758	-0.026334	9.856275	0.045032	0.092329	-0.035173
+12.147155	0.069427	-0.009576	9.829940	0.047697	0.088599	-0.038504
+12.148156	0.002394	-0.014364	9.827546	0.048496	0.087666	-0.039570
+12.149154	-0.014364	0.040699	9.832334	0.047564	0.090198	-0.039570
+12.150108	-0.055063	0.045487	9.791636	0.045165	0.089398	-0.037838
+12.151154	0.035911	0.035911	9.810788	0.044100	0.088199	-0.035040
+12.152156	-0.007182	0.014364	9.849093	0.047164	0.089398	-0.031309
+12.153090	-0.035911	-0.035911	9.844305	0.047430	0.086201	-0.032775
+12.154111	-0.014364	-0.011970	9.789242	0.047830	0.087666	-0.031975
+12.155160	-0.026334	-0.019152	9.796424	0.046897	0.090198	-0.035573
+12.156156	-0.055063	-0.059851	9.827546	0.045165	0.089931	-0.034773
+12.157156	0.035911	0.014364	9.825152	0.045698	0.087799	-0.036239
+12.158159	0.035911	-0.004788	9.736573	0.048363	0.088066	-0.037305
+12.159155	0.002394	0.031123	9.750937	0.049562	0.088066	-0.036239
+12.160155	0.014364	0.002394	9.806000	0.047697	0.084069	-0.034374
+12.161111	0.038305	0.000000	9.789242	0.046231	0.084202	-0.033574
+12.162112	0.019152	0.014364	9.803606	0.047564	0.087666	-0.037305
+12.163086	-0.026334	-0.047881	9.798818	0.048096	0.085934	-0.036905
+12.164142	0.002394	-0.062245	9.853881	0.049828	0.085534	-0.034240
+12.165107	-0.069427	-0.045487	9.813182	0.048896	0.086467	-0.033175
+12.166092	-0.021546	0.000000	9.765301	0.048763	0.088332	-0.039969
+12.167156	0.009576	0.050275	9.789242	0.046897	0.088332	-0.037838
+12.168154	0.011970	-0.011970	9.794030	0.043433	0.087400	-0.037571
+12.169169	0.000000	0.026334	9.808394	0.045432	0.087133	-0.036239
+12.170088	0.033517	-0.004788	9.731785	0.048629	0.088466	-0.035173
+12.171111	-0.016758	0.023940	9.717420	0.048763	0.089265	-0.037038
+12.172113	0.028729	-0.002394	9.724603	0.046764	0.089398	-0.038371
+12.173158	0.021546	0.028729	9.796424	0.045032	0.087533	-0.036905
+12.174159	0.043093	0.007182	9.817970	0.045165	0.085002	-0.038371
+12.175155	0.016758	-0.047881	9.755725	0.047963	0.088332	-0.036905
+12.176155	0.035911	0.000000	9.815576	0.048363	0.091663	-0.036106
+12.177157	0.007182	-0.004788	9.827546	0.047564	0.091130	-0.036505
+12.178158	0.021546	0.038305	9.738967	0.046498	0.087266	-0.037172
+12.179155	0.043093	-0.009576	9.815576	0.047430	0.085668	-0.035839
+12.180110	0.045487	-0.057457	9.722208	0.048363	0.086867	-0.040769
+12.181099	-0.014364	-0.007182	9.789242	0.049429	0.088332	-0.038237
+12.182143	0.011970	-0.004788	9.806000	0.046764	0.088066	-0.033175
+12.183156	0.031123	-0.038305	9.827546	0.043966	0.087799	-0.033974
+12.184156	0.045487	-0.045487	9.822758	0.043433	0.085934	-0.035306
+12.185113	0.009576	-0.004788	9.827546	0.046498	0.087000	-0.036372
+12.186157	-0.045487	-0.004788	9.825152	0.049296	0.086201	-0.035040
+12.187153	-0.002394	0.002394	9.758119	0.047297	0.087400	-0.034773
+12.188154	-0.004788	-0.004788	9.796424	0.046364	0.086467	-0.038770
+12.189113	0.047881	-0.021546	9.825152	0.046098	0.088466	-0.041568
+12.190053	-0.007182	-0.009576	9.875427	0.047297	0.088332	-0.036905
+12.191135	0.062245	-0.016758	9.726997	0.046897	0.088998	-0.033841
+12.192156	0.100550	-0.040699	9.762907	0.045698	0.089132	-0.037571
+12.193131	0.021546	-0.028729	9.791636	0.046364	0.088332	-0.038371
+12.194075	0.026334	-0.019152	9.770089	0.045565	0.088066	-0.034374
+12.195110	0.009576	0.004788	9.791636	0.047297	0.089398	-0.035839
+12.196155	0.023940	-0.043093	9.810788	0.049296	0.085534	-0.036372
+12.197155	0.043093	0.009576	9.832334	0.047963	0.085268	-0.036239
+12.198120	0.033517	0.011970	9.794030	0.045432	0.084735	-0.036505
+12.199068	0.000000	-0.014364	9.858669	0.044233	0.086467	-0.034240
+12.200084	0.033517	-0.023940	9.873033	0.045698	0.087400	-0.034240
+12.201157	0.011970	-0.014364	9.813182	0.046897	0.089531	-0.035440
+12.202111	0.000000	-0.004788	9.801212	0.044766	0.090464	-0.036239
+12.203155	-0.038305	-0.033517	9.815576	0.043167	0.086600	-0.038637
+12.204154	0.004788	-0.035911	9.853881	0.045565	0.083669	-0.038371
+12.205155	0.055063	-0.019152	9.858669	0.045299	0.085002	-0.037172
+12.206159	0.002394	-0.043093	9.803606	0.045698	0.087133	-0.039170
+12.207155	-0.004788	-0.007182	9.810788	0.048763	0.087400	-0.040769
+12.208109	0.023940	0.007182	9.870639	0.047297	0.087666	-0.039037
+12.209150	-0.009576	-0.019152	9.863457	0.044366	0.088066	-0.039703
+12.210112	0.011970	-0.033517	9.817970	0.045565	0.090198	-0.034907
+12.211111	0.002394	-0.009576	9.810788	0.048096	0.088998	-0.032508
+12.212156	-0.033517	0.031123	9.844305	0.048096	0.087666	-0.038237
+12.213157	-0.007182	0.031123	9.760513	0.046631	0.087266	-0.037038
+12.214093	0.007182	-0.019152	9.791636	0.044233	0.087799	-0.035972
+12.215118	0.033517	0.014364	9.820364	0.044766	0.084602	-0.033708
+12.216081	0.014364	0.052669	9.784454	0.046231	0.085268	-0.035173
+12.217094	0.009576	0.026334	9.798818	0.046631	0.087666	-0.035306
+12.218124	-0.009576	0.009576	9.762907	0.047031	0.089398	-0.039836
+12.219155	0.038305	0.043093	9.703056	0.047963	0.087533	-0.044233
+12.220154	-0.016758	0.074215	9.734179	0.047564	0.087533	-0.039570
+12.221154	-0.064639	0.045487	9.770089	0.044499	0.089931	-0.035839
+12.222112	-0.038305	-0.035911	9.801212	0.043966	0.088199	-0.035040
+12.223154	-0.055063	0.002394	9.837123	0.045965	0.086334	-0.034907
+12.224154	-0.009576	-0.043093	9.856275	0.045965	0.085002	-0.036639
+12.225109	0.011970	-0.059851	9.810788	0.045832	0.087400	-0.036106
+12.226105	0.002394	0.009576	9.829940	0.048230	0.089398	-0.035839
+12.227091	0.028729	0.021546	9.758119	0.048763	0.087533	-0.037571
+12.228154	0.002394	0.007182	9.858669	0.046764	0.086600	-0.037038
+12.229153	-0.040699	0.004788	9.803606	0.045032	0.089265	-0.036639
+12.230110	-0.040699	0.045487	9.774877	0.044766	0.090864	-0.038904
+12.231107	-0.076609	0.007182	9.846699	0.044499	0.089931	-0.035839
+12.232086	0.000000	0.050275	9.815576	0.045032	0.088865	-0.035440
+12.233156	0.019152	0.026334	9.806000	0.047430	0.088732	-0.035173
+12.234156	0.014364	-0.047881	9.829940	0.047297	0.088732	-0.035839
+12.235080	0.011970	-0.004788	9.784454	0.044766	0.088066	-0.037838
+12.236073	0.009576	-0.033517	9.777271	0.047031	0.084335	-0.035706
+12.237156	-0.004788	-0.023940	9.758119	0.051161	0.086067	-0.035040
+12.238158	0.007182	0.004788	9.832334	0.048096	0.088998	-0.035306
+12.239093	0.002394	0.019152	9.825152	0.047297	0.088199	-0.034507
+12.240157	0.009576	-0.028729	9.877821	0.047564	0.086067	-0.031176
+12.241111	-0.033517	-0.014364	9.913732	0.046498	0.088066	-0.035972
+12.242158	-0.040699	0.007182	9.856275	0.047564	0.087933	-0.037038
+12.243156	0.035911	0.004788	9.803606	0.047430	0.087000	-0.035040
+12.244096	0.040699	-0.045487	9.868245	0.045165	0.085002	-0.036239
+12.245114	-0.009576	-0.059851	9.853881	0.044233	0.085534	-0.035440
+12.246161	0.000000	-0.023940	9.801212	0.045432	0.085401	-0.033041
+12.247155	-0.004788	-0.016758	9.825152	0.045565	0.085002	-0.034640
+12.248156	-0.057457	0.009576	9.717420	0.046897	0.087666	-0.035440
+12.249156	-0.028729	-0.033517	9.700662	0.045832	0.087666	-0.034640
+12.250108	-0.021546	-0.043093	9.798818	0.047164	0.089665	-0.036905
+12.251084	0.019152	-0.011970	9.726997	0.048096	0.088599	-0.036905
+12.252156	0.019152	-0.004788	9.734179	0.047963	0.087400	-0.037305
+12.253155	-0.028729	-0.038305	9.772483	0.047697	0.085401	-0.033841
+12.254112	0.033517	0.035911	9.806000	0.047031	0.085668	-0.034240
+12.255149	0.038305	-0.009576	9.820364	0.050228	0.088998	-0.034640
+12.256098	-0.014364	0.016758	9.767695	0.050628	0.090997	-0.035040
+12.257096	0.004788	-0.009576	9.753331	0.048363	0.087400	-0.033974
+12.258098	-0.019152	-0.004788	9.731785	0.046098	0.086201	-0.033175
+12.259095	0.016758	-0.026334	9.832334	0.045832	0.087666	-0.036372
+12.260099	0.040699	0.002394	9.784454	0.046631	0.089265	-0.035972
+12.261069	0.069427	0.028729	9.741361	0.047164	0.089132	-0.036639
+12.262158	0.052669	0.026334	9.801212	0.046498	0.087666	-0.041035
+12.263154	0.050275	-0.033517	9.849093	0.048896	0.086600	-0.041035
+12.264096	-0.002394	0.050275	9.760513	0.049562	0.086867	-0.037038
+12.265154	-0.014364	-0.026334	9.794030	0.046498	0.086734	-0.036505
+12.266124	0.057457	-0.016758	9.815576	0.047164	0.088599	-0.037038
+12.267155	0.057457	-0.004788	9.813182	0.048896	0.090064	-0.037172
+12.268154	0.002394	0.009576	9.784454	0.046364	0.087799	-0.037172
+12.269107	0.021546	0.026334	9.861063	0.046231	0.088998	-0.038237
+12.270085	0.023940	0.059851	9.863457	0.048496	0.090864	-0.036772
+12.271157	-0.023940	-0.004788	9.760513	0.047963	0.091930	-0.036372
+12.272155	-0.028729	0.004788	9.750937	0.047564	0.088332	-0.037038
+12.273155	-0.009576	0.004788	9.772483	0.047031	0.085668	-0.035839
+12.274094	-0.023940	-0.007182	9.789242	0.047297	0.087400	-0.038237
+12.275152	0.009576	0.057457	9.844305	0.048096	0.086867	-0.039436
+12.276158	0.023940	0.007182	9.798818	0.048096	0.087533	-0.036106
+12.277155	-0.038305	-0.019152	9.794030	0.048230	0.087666	-0.035440
+12.278158	-0.055063	0.007182	9.820364	0.047031	0.087533	-0.035173
+12.279154	-0.038305	0.000000	9.810788	0.047031	0.086467	-0.038770
+12.280115	0.000000	-0.035911	9.827546	0.047963	0.086867	-0.037172
+12.281156	0.057457	-0.023940	9.853881	0.048629	0.086600	-0.034773
+12.282111	0.057457	-0.023940	9.853881	0.048096	0.086334	-0.033441
+12.283085	0.000000	-0.052669	9.825152	0.045032	0.088466	-0.036639
+12.284152	0.009576	-0.035911	9.904156	0.044899	0.088332	-0.039703
+12.285109	0.021546	-0.038305	9.906550	0.043966	0.088865	-0.036372
+12.286160	0.011970	-0.026334	9.851487	0.043833	0.087533	-0.036505
+12.287156	0.026334	0.014364	9.841911	0.045432	0.085934	-0.035040
+12.288156	0.000000	-0.007182	9.827546	0.048363	0.086734	-0.036106
+12.289097	0.019152	-0.019152	9.870639	0.048629	0.088998	-0.036239
+12.290158	0.045487	0.031123	9.827546	0.047430	0.090597	-0.035839
+12.291111	0.033517	0.040699	9.856275	0.047430	0.087799	-0.037438
+12.292110	-0.002394	0.033517	9.865851	0.045165	0.085801	-0.035173
+12.293058	-0.007182	0.031123	9.789242	0.045165	0.086867	-0.037305
+12.294065	-0.007182	-0.014364	9.765301	0.047830	0.088466	-0.038104
+12.295055	0.016758	-0.023940	9.765301	0.049162	0.090864	-0.035706
+12.296078	-0.031123	0.055063	9.858669	0.048896	0.090331	-0.036905
+12.297081	0.021546	0.007182	9.734179	0.046498	0.091130	-0.037038
+12.298086	-0.002394	-0.009576	9.784454	0.046764	0.088066	-0.033974
+12.299082	-0.002394	-0.004788	9.774877	0.047297	0.085934	-0.036505
+12.300082	-0.019152	-0.019152	9.726997	0.046364	0.085401	-0.037172
+12.301082	-0.023940	-0.023940	9.779666	0.046631	0.087666	-0.035573
+12.302015	-0.009576	-0.011970	9.731785	0.048763	0.087000	-0.034240
+12.303010	0.007182	0.043093	9.789242	0.047830	0.086600	-0.037172
+12.304094	-0.033517	0.033517	9.827546	0.047564	0.087400	-0.035972
+12.305081	-0.028729	-0.009576	9.861063	0.044766	0.083802	-0.036772
+12.306020	-0.014364	-0.007182	9.827546	0.045032	0.084602	-0.034640
+12.307031	0.000000	0.014364	9.810788	0.046364	0.087666	-0.034374
+12.308015	0.050275	0.002394	9.755725	0.047697	0.088199	-0.037438
+12.309008	0.019152	-0.023940	9.851487	0.048496	0.089931	-0.039703
+12.310017	0.016758	-0.019152	9.865851	0.048230	0.090331	-0.036372
+12.311017	-0.016758	-0.019152	9.808394	0.046631	0.092063	-0.037172
+12.312007	0.035911	-0.040699	9.803606	0.047297	0.090464	-0.036639
+12.313017	0.093368	0.002394	9.784454	0.048096	0.087266	-0.033974
+12.314028	0.050275	-0.011970	9.844305	0.047830	0.086334	-0.032642
+12.315029	-0.011970	-0.033517	9.837123	0.046897	0.087533	-0.033175
+12.316027	-0.007182	-0.023940	9.820364	0.048230	0.087400	-0.033574
+12.317027	0.000000	-0.007182	9.832334	0.047430	0.088599	-0.034107
+12.318015	-0.002394	-0.019152	9.803606	0.048629	0.089398	-0.035839
+12.319029	-0.038305	0.000000	9.837123	0.048230	0.089531	-0.037571
+12.320028	-0.040699	0.035911	9.827546	0.047430	0.088998	-0.035040
+12.321030	-0.011970	-0.016758	9.772483	0.048230	0.090730	-0.034507
+12.322075	0.002394	0.011970	9.865851	0.047564	0.091130	-0.037172
+12.323102	0.043093	-0.021546	9.853881	0.045165	0.089398	-0.037971
+12.324104	0.052669	-0.021546	9.832334	0.044233	0.087666	-0.038904
+12.325099	0.011970	-0.098156	9.791636	0.047164	0.087933	-0.035706
+12.326049	0.007182	-0.040699	9.815576	0.049296	0.086734	-0.035173
+12.327104	0.011970	0.014364	9.803606	0.047697	0.087000	-0.037704
+12.328103	0.028729	-0.002394	9.719814	0.047430	0.087266	-0.035573
+12.329104	0.028729	0.038305	9.765301	0.046897	0.087799	-0.034107
+12.330112	0.057457	-0.007182	9.710238	0.045698	0.086600	-0.035839
+12.331048	0.083792	-0.004788	9.755725	0.045032	0.088466	-0.033574
+12.332027	0.019152	-0.019152	9.746149	0.045165	0.088466	-0.034107
+12.333045	0.004788	0.016758	9.777271	0.045832	0.085135	-0.035972
+12.334106	0.019152	-0.007182	9.863457	0.046364	0.084202	-0.035440
+12.335097	0.011970	-0.035911	9.901762	0.046364	0.087666	-0.034507
+12.336103	-0.009576	-0.052669	9.822758	0.047031	0.089665	-0.036639
+12.337104	-0.014364	-0.028729	9.755725	0.046631	0.089132	-0.039303
+12.338106	-0.011970	0.069427	9.810788	0.046364	0.089398	-0.034640
+12.339090	0.000000	0.064639	9.772483	0.045698	0.087799	-0.034240
+12.340049	0.004788	0.021546	9.782060	0.044233	0.086067	-0.038904
+12.341044	0.002394	-0.019152	9.825152	0.043567	0.086867	-0.036639
+12.342088	0.031123	-0.033517	9.825152	0.044233	0.088865	-0.034107
+12.343102	0.026334	-0.031123	9.794030	0.046364	0.088199	-0.033974
+12.344031	0.040699	-0.038305	9.784454	0.046364	0.087133	-0.035706
+12.345108	0.050275	0.016758	9.736573	0.046631	0.088732	-0.041035
+12.346108	0.031123	-0.019152	9.820364	0.048496	0.089398	-0.039170
+12.347099	-0.002394	-0.026334	9.865851	0.046897	0.088066	-0.038371
+12.348102	-0.004788	0.007182	9.853881	0.046631	0.087533	-0.038504
+12.349104	-0.023940	0.040699	9.803606	0.048896	0.089798	-0.037038
+12.350070	0.071821	0.004788	9.770089	0.047830	0.089798	-0.036239
+12.351051	0.028729	0.016758	9.755725	0.045832	0.087533	-0.033175
+12.352101	0.009576	0.016758	9.815576	0.045965	0.086867	-0.034640
+12.353104	0.069427	0.009576	9.726997	0.047297	0.087533	-0.036905
+12.354106	0.021546	0.021546	9.755725	0.044499	0.088865	-0.037571
+12.355104	0.004788	-0.011970	9.722208	0.043833	0.088865	-0.034907
+12.356102	-0.031123	0.021546	9.710238	0.047963	0.087400	-0.035040
+12.357102	-0.014364	0.031123	9.688692	0.048629	0.087000	-0.037838
+12.358106	0.009576	-0.014364	9.853881	0.047830	0.089132	-0.038770
+12.359102	0.028729	0.028729	9.815576	0.047031	0.087933	-0.040103
+12.360048	0.043093	0.050275	9.815576	0.048763	0.088865	-0.037704
+12.361094	0.052669	0.000000	9.774877	0.047164	0.090198	-0.033841
+12.362072	-0.011970	0.004788	9.806000	0.047963	0.088199	-0.034240
+12.363098	0.009576	-0.009576	9.758119	0.048230	0.086867	-0.035440
+12.364073	-0.021546	0.011970	9.813182	0.046764	0.089132	-0.035972
+12.365067	0.002394	0.050275	9.784454	0.048496	0.089931	-0.038237
+12.366107	-0.002394	0.014364	9.772483	0.049029	0.086600	-0.038504
+12.367056	0.021546	-0.023940	9.856275	0.045165	0.083802	-0.036106
+12.368102	-0.011970	-0.011970	9.834729	0.044899	0.086734	-0.034107
+12.369104	0.028729	-0.019152	9.861063	0.047963	0.088199	-0.035573
+12.370078	0.007182	0.007182	9.820364	0.048629	0.088599	-0.036505
+12.371145	-0.009576	0.052669	9.846699	0.050095	0.088998	-0.036772
+12.372154	-0.007182	-0.019152	9.918520	0.048096	0.087400	-0.036106
+12.373154	-0.050275	-0.019152	9.858669	0.047697	0.089665	-0.037172
+12.374073	-0.007182	-0.002394	9.832334	0.046498	0.087666	-0.035573
+12.375153	0.033517	-0.011970	9.844305	0.045299	0.088066	-0.035040
+12.376153	-0.011970	-0.004788	9.724603	0.045965	0.090864	-0.036239
+12.377153	-0.040699	-0.043093	9.688692	0.045698	0.089665	-0.035706
+12.378107	-0.014364	-0.023940	9.753331	0.047164	0.087133	-0.037038
+12.379108	0.040699	0.009576	9.758119	0.047430	0.085534	-0.039570
+12.380144	0.016758	0.014364	9.746149	0.047564	0.085934	-0.039037
+12.381152	0.011970	0.031123	9.767695	0.046231	0.087799	-0.035706
+12.382156	0.016758	0.045487	9.875427	0.047297	0.088732	-0.035306
+12.383107	-0.026334	0.000000	9.908944	0.048096	0.085668	-0.039570
+12.384081	0.028729	-0.019152	9.870639	0.045698	0.084602	-0.038504
+12.385081	0.028729	0.021546	9.724603	0.045698	0.086334	-0.033974
+12.386076	-0.026334	0.016758	9.808394	0.045832	0.087666	-0.034374
+12.387150	-0.064639	-0.033517	9.868245	0.046631	0.088998	-0.035573
+12.388091	-0.019152	0.007182	9.796424	0.047564	0.088865	-0.035040
+12.389080	0.031123	-0.023940	9.774877	0.048363	0.086867	-0.034907
+12.390081	0.040699	-0.019152	9.767695	0.048230	0.084469	-0.036505
+12.391077	0.002394	-0.023940	9.851487	0.048096	0.087933	-0.034507
+12.392081	0.059851	-0.014364	9.870639	0.046231	0.090464	-0.037438
+12.393109	0.043093	0.007182	9.825152	0.046498	0.091130	-0.039969
+12.394060	0.033517	-0.021546	9.774877	0.047830	0.088199	-0.040902
+12.395087	0.014364	-0.038305	9.743755	0.046231	0.089798	-0.038770
+12.396081	0.045487	-0.069427	9.853881	0.047697	0.090198	-0.036505
+12.397087	-0.033517	0.007182	9.889792	0.046498	0.089132	-0.034773
+12.398027	-0.009576	-0.004788	9.808394	0.046098	0.090064	-0.035173
+12.399072	-0.045487	-0.011970	9.825152	0.045965	0.089931	-0.037838
+12.400028	-0.019152	-0.014364	9.870639	0.045965	0.089531	-0.039303
+12.401059	0.069427	-0.011970	9.815576	0.047297	0.090198	-0.036772
+12.402045	0.047881	0.000000	9.760513	0.045565	0.088599	-0.037172
+12.403075	0.071821	0.016758	9.813182	0.045032	0.087666	-0.036239
+12.404102	0.043093	-0.023940	9.789242	0.045432	0.088865	-0.038371
+12.405102	0.019152	-0.023940	9.705450	0.046231	0.087533	-0.038770
+12.406085	0.007182	-0.004788	9.746149	0.047297	0.084069	-0.034107
+12.407103	-0.007182	0.009576	9.789242	0.046897	0.084069	-0.040103
+12.408043	0.069427	0.000000	9.861063	0.046098	0.087000	-0.040103
+12.409046	0.007182	-0.031123	9.829940	0.044899	0.086734	-0.039303
+12.410028	0.026334	-0.047881	9.772483	0.045432	0.088199	-0.035306
+12.411100	0.023940	-0.019152	9.815576	0.047031	0.087266	-0.034907
+12.412101	0.035911	-0.004788	9.767695	0.048096	0.086334	-0.034773
+12.413101	0.009576	0.004788	9.777271	0.047963	0.087000	-0.034773
+12.414106	-0.057457	-0.009576	9.789242	0.044233	0.089132	-0.035440
+12.415102	-0.031123	-0.002394	9.825152	0.044366	0.090997	-0.036372
+12.416101	-0.007182	0.007182	9.817970	0.048363	0.090064	-0.040769
+12.417103	-0.007182	0.021546	9.825152	0.047697	0.089665	-0.041435
+12.418046	0.014364	0.002394	9.810788	0.046631	0.090331	-0.034240
+12.419105	0.000000	-0.026334	9.849093	0.048496	0.087400	-0.035573
+12.420048	0.045487	-0.055063	9.758119	0.048096	0.085268	-0.038237
+12.421037	0.026334	-0.016758	9.806000	0.046364	0.086201	-0.039969
+12.422106	0.028729	0.014364	9.806000	0.045165	0.087000	-0.039969
+12.423101	0.090974	0.000000	9.863457	0.045432	0.085934	-0.037704
+12.424101	0.021546	0.014364	9.784454	0.047164	0.087933	-0.035573
+12.425104	-0.004788	0.016758	9.832334	0.049695	0.089265	-0.037038
+12.426102	-0.021546	0.023940	9.822758	0.049695	0.090064	-0.037438
+12.427105	0.028729	0.014364	9.789242	0.048629	0.088998	-0.037971
+12.428103	0.002394	0.004788	9.767695	0.048896	0.088199	-0.035040
+12.429060	0.035911	-0.026334	9.753331	0.046364	0.086867	-0.033974
+12.430033	0.014364	-0.007182	9.748543	0.046764	0.085534	-0.035839
+12.431099	0.045487	-0.028729	9.868245	0.049562	0.086201	-0.036505
+12.432106	-0.021546	-0.052669	9.904156	0.049562	0.087799	-0.035040
+12.433104	0.011970	-0.043093	9.849093	0.047963	0.086734	-0.035839
+12.434105	0.033517	-0.057457	9.887397	0.046498	0.087000	-0.037305
+12.435036	0.009576	-0.038305	9.861063	0.044233	0.087000	-0.037172
+12.436103	-0.045487	-0.023940	9.786848	0.043700	0.088332	-0.034773
+12.437101	0.047881	-0.023940	9.791636	0.046098	0.088998	-0.033441
+12.438102	-0.009576	-0.050275	9.810788	0.047963	0.087400	-0.034773
+12.439108	0.004788	-0.021546	9.755725	0.048629	0.087400	-0.035706
+12.440056	0.009576	-0.033517	9.777271	0.046631	0.085534	-0.036772
+12.441094	0.052669	0.011970	9.796424	0.046364	0.086067	-0.035173
+12.442106	-0.002394	0.007182	9.825152	0.046631	0.085668	-0.036372
+12.443102	-0.004788	0.009576	9.894580	0.047031	0.089132	-0.039037
+12.444050	-0.021546	-0.019152	9.755725	0.044366	0.087133	-0.037704
+12.445102	0.000000	-0.052669	9.796424	0.044499	0.087000	-0.033841
+12.446106	-0.040699	0.009576	9.815576	0.045565	0.087133	-0.033708
+12.447098	-0.028729	-0.007182	9.750937	0.044899	0.088732	-0.034107
+12.448103	0.033517	-0.028729	9.664751	0.046098	0.086867	-0.035839
+12.449071	0.009576	-0.064639	9.669540	0.047564	0.085801	-0.036905
+12.450085	0.019152	-0.021546	9.837123	0.049029	0.086334	-0.033574
+12.451058	0.019152	-0.052669	9.803606	0.047164	0.087933	-0.036505
+12.452102	0.019152	-0.062245	9.688692	0.046231	0.085934	-0.039436
+12.453101	-0.031123	-0.095762	9.703056	0.048096	0.086867	-0.038371
+12.454091	0.011970	-0.074215	9.767695	0.047031	0.089665	-0.036106
+12.455102	0.002394	-0.023940	9.755725	0.045832	0.089665	-0.035839
+12.456101	-0.011970	-0.023940	9.770089	0.045299	0.088199	-0.036239
+12.457102	-0.035911	-0.095762	9.844305	0.045165	0.088199	-0.037571
+12.458104	0.002394	-0.083792	9.767695	0.046498	0.087400	-0.041035
+12.459080	-0.023940	0.043093	9.810788	0.046498	0.087266	-0.037172
+12.460057	0.019152	0.057457	9.829940	0.047164	0.088998	-0.035573
+12.461100	-0.009576	-0.019152	9.803606	0.047830	0.089931	-0.037838
+12.462105	-0.007182	-0.004788	9.801212	0.046764	0.087666	-0.036905
+12.463046	0.011970	-0.009576	9.772483	0.047430	0.087933	-0.036239
+12.464092	0.052669	0.031123	9.741361	0.046764	0.089132	-0.034240
+12.465102	0.016758	0.000000	9.825152	0.047164	0.088732	-0.032642
+12.466105	0.019152	-0.026334	9.829940	0.046498	0.088199	-0.032242
+12.467103	0.047881	-0.026334	9.789242	0.046631	0.088199	-0.034240
+12.468097	-0.016758	-0.047881	9.806000	0.046764	0.089798	-0.037571
+12.469102	0.019152	-0.040699	9.806000	0.047830	0.089132	-0.035706
+12.470086	0.023940	0.014364	9.789242	0.045965	0.087799	-0.034107
+12.471074	-0.004788	0.016758	9.834729	0.044233	0.089798	-0.035706
+12.472069	0.026334	0.016758	9.786848	0.046231	0.088865	-0.038770
+12.473074	-0.014364	0.059851	9.822758	0.049296	0.083936	-0.036372
+12.474074	0.045487	0.038305	9.806000	0.048230	0.082870	-0.034773
+12.475067	0.055063	0.004788	9.755725	0.046631	0.084868	-0.036106
+12.476072	-0.007182	-0.014364	9.832334	0.048496	0.087666	-0.037305
+12.477072	-0.016758	-0.004788	9.892186	0.048230	0.090464	-0.036639
+12.478073	0.031123	-0.021546	9.849093	0.046098	0.089931	-0.040902
+12.479071	-0.016758	0.014364	9.729391	0.047031	0.088199	-0.040369
+12.480101	0.004788	-0.052669	9.738967	0.047430	0.087799	-0.035706
+12.481109	-0.019152	-0.045487	9.794030	0.045832	0.086734	-0.037971
+12.482034	-0.038305	-0.031123	9.798818	0.045432	0.085668	-0.039170
+12.483129	-0.004788	-0.026334	9.832334	0.044899	0.081671	-0.037438
+12.484101	0.050275	-0.069427	9.789242	0.045832	0.083003	-0.035440
+12.485098	0.014364	-0.031123	9.758119	0.046498	0.085135	-0.035306
+12.486104	0.009576	0.007182	9.712632	0.046764	0.087933	-0.032908
+12.487101	0.059851	-0.014364	9.770089	0.045565	0.087933	-0.035706
+12.488101	0.059851	-0.040699	9.779666	0.044632	0.088732	-0.033974
+12.489102	0.038305	-0.079003	9.765301	0.045299	0.088599	-0.031975
+12.490039	0.028729	0.023940	9.786848	0.046631	0.086600	-0.031709
+12.491075	-0.011970	-0.059851	9.806000	0.049296	0.086067	-0.033308
+12.492063	0.023940	-0.019152	9.767695	0.050095	0.088599	-0.037571
+12.493101	0.002394	0.007182	9.825152	0.047564	0.089665	-0.040103
+12.494104	-0.047881	-0.011970	9.885003	0.046231	0.088998	-0.037038
+12.495101	0.033517	0.014364	9.782060	0.044766	0.089531	-0.038104
+12.496101	-0.004788	0.047881	9.901762	0.045165	0.088066	-0.038637
+12.497103	-0.047881	0.000000	9.822758	0.047697	0.086067	-0.038237
+12.498105	0.004788	0.004788	9.786848	0.047830	0.087266	-0.033441
+12.499066	0.004788	-0.047881	9.782060	0.046631	0.089132	-0.031842
+12.500103	-0.035911	0.009576	9.861063	0.046764	0.088998	-0.032642
+12.501104	0.007182	0.031123	9.887397	0.048096	0.086734	-0.032242
+12.502047	-0.035911	0.033517	9.851487	0.048096	0.088998	-0.033708
+12.503098	-0.002394	-0.014364	9.815576	0.047697	0.087400	-0.034374
+12.504103	-0.011970	-0.064639	9.837123	0.045565	0.089265	-0.035040
+12.505104	0.016758	-0.028729	9.779666	0.045432	0.090064	-0.035573
+12.506107	0.009576	0.033517	9.712632	0.047164	0.089398	-0.035040
+12.507101	0.021546	0.035911	9.798818	0.047031	0.088998	-0.035839
+12.508101	0.002394	-0.009576	9.782060	0.045432	0.088066	-0.037571
+12.509096	0.007182	-0.002394	9.829940	0.045698	0.086467	-0.039170
+12.510105	0.016758	-0.014364	9.786848	0.046098	0.086201	-0.037971
+12.511100	0.019152	-0.045487	9.863457	0.047297	0.087400	-0.036639
+12.512044	0.043093	0.000000	9.798818	0.049162	0.089665	-0.036239
+12.513100	0.067033	0.059851	9.755725	0.049562	0.091130	-0.038104
+12.514085	0.021546	0.021546	9.837123	0.046364	0.090864	-0.038371
+12.515073	-0.040699	0.026334	9.846699	0.045832	0.087533	-0.037038
+12.516103	0.004788	0.000000	9.782060	0.045299	0.088466	-0.034240
+12.517102	0.038305	0.002394	9.794030	0.045032	0.087133	-0.034773
+12.518099	0.014364	0.002394	9.798818	0.048896	0.086867	-0.034773
+12.519064	-0.033517	0.014364	9.813182	0.049828	0.086600	-0.037971
+12.520030	0.016758	-0.055063	9.779666	0.048629	0.086467	-0.036905
+12.521077	0.033517	-0.028729	9.810788	0.046364	0.087533	-0.035440
+12.522078	-0.055063	-0.004788	9.827546	0.045565	0.090198	-0.036772
+12.523102	-0.055063	0.000000	9.827546	0.047564	0.088199	-0.037438
+12.524102	-0.016758	0.014364	9.885003	0.048763	0.088199	-0.036905
+12.525105	-0.033517	-0.009576	9.815576	0.047697	0.089265	-0.037305
+12.526104	0.002394	0.002394	9.825152	0.047564	0.089132	-0.037038
+12.527101	0.004788	-0.009576	9.796424	0.045565	0.089132	-0.032642
+12.528101	0.000000	-0.011970	9.841911	0.044499	0.087666	-0.034640
+12.529087	0.014364	0.004788	9.810788	0.046498	0.087266	-0.037038
+12.530103	-0.033517	-0.009576	9.858669	0.049029	0.090864	-0.037838
+12.531064	-0.002394	0.023940	9.765301	0.051427	0.089132	-0.040369
+12.532024	0.031123	-0.002394	9.808394	0.049695	0.087666	-0.037305
+12.533072	0.055063	0.028729	9.877821	0.044366	0.088865	-0.035040
+12.534047	0.014364	0.000000	9.861063	0.045299	0.088332	-0.035573
+12.535045	0.004788	0.045487	9.784454	0.046631	0.088865	-0.035839
+12.536087	0.038305	0.009576	9.734179	0.047164	0.092329	-0.036239
+12.537101	0.026334	0.043093	9.746149	0.047697	0.091397	-0.035173
+12.538074	0.031123	0.021546	9.849093	0.048763	0.087000	-0.033441
+12.539100	0.055063	-0.007182	9.851487	0.047564	0.085934	-0.037571
+12.540101	0.023940	0.004788	9.772483	0.043966	0.086467	-0.036772
+12.541102	0.004788	0.011970	9.762907	0.043300	0.088332	-0.035839
+12.542088	0.035911	0.021546	9.839517	0.045698	0.088066	-0.036106
+12.543060	0.019152	0.000000	9.798818	0.046631	0.089132	-0.034240
+12.544099	0.055063	0.009576	9.738967	0.048230	0.088865	-0.038504
+12.545043	0.021546	-0.069427	9.712632	0.049296	0.089798	-0.039037
+12.546074	0.007182	-0.002394	9.782060	0.048230	0.090331	-0.037571
+12.547100	-0.033517	0.033517	9.889792	0.045299	0.091530	-0.039170
+12.548101	-0.019152	0.004788	9.825152	0.047164	0.088998	-0.040902
+12.549101	-0.007182	-0.002394	9.767695	0.047430	0.087266	-0.042101
+12.550038	0.011970	-0.021546	9.810788	0.047830	0.089531	-0.037305
+12.551044	0.002394	-0.026334	9.738967	0.047963	0.090064	-0.035040
+12.552100	0.019152	-0.052669	9.782060	0.047963	0.089398	-0.034507
+12.553057	0.000000	-0.033517	9.832334	0.047164	0.088998	-0.036106
+12.554130	-0.021546	-0.019152	9.770089	0.048096	0.087400	-0.035839
+12.555100	0.016758	-0.021546	9.817970	0.049562	0.084735	-0.036106
+12.556100	-0.014364	-0.047881	9.841911	0.047697	0.083936	-0.038237
+12.557100	-0.026334	-0.002394	9.870639	0.046498	0.086201	-0.037305
+12.558103	-0.050275	-0.021546	9.853881	0.044100	0.087666	-0.036239
+12.559032	-0.052669	0.002394	9.784454	0.046498	0.088466	-0.036239
+12.560100	-0.021546	-0.047881	9.794030	0.050894	0.090198	-0.035706
+12.561090	0.043093	0.028729	9.813182	0.050894	0.089931	-0.037172
+12.562070	0.050275	-0.016758	9.731785	0.049562	0.087133	-0.037838
+12.563031	0.052669	0.000000	9.767695	0.048896	0.086867	-0.035706
+12.564024	0.055063	0.052669	9.803606	0.048230	0.087666	-0.036772
+12.565100	0.076609	0.031123	9.789242	0.047430	0.089132	-0.036772
+12.566104	0.028729	-0.009576	9.808394	0.045432	0.087933	-0.035040
+12.567096	0.021546	-0.035911	9.868245	0.046498	0.087266	-0.035173
+12.568086	0.004788	-0.011970	9.873033	0.048896	0.087533	-0.037704
+12.569102	0.067033	-0.023940	9.875427	0.049162	0.085268	-0.038237
+12.570104	0.071821	0.023940	9.784454	0.047697	0.086467	-0.039170
+12.571101	0.038305	-0.047881	9.734179	0.047164	0.087933	-0.037438
+12.572100	0.033517	-0.019152	9.817970	0.045565	0.087799	-0.035440
+12.573087	0.043093	0.019152	9.777271	0.043433	0.090064	-0.033574
+12.574107	-0.004788	0.004788	9.794030	0.045032	0.090997	-0.034907
+12.575099	-0.019152	-0.023940	9.839517	0.045032	0.089398	-0.035573
+12.576100	0.052669	-0.004788	9.825152	0.047297	0.086067	-0.037571
+12.577076	0.033517	-0.016758	9.753331	0.046897	0.088332	-0.036905
+12.578100	-0.007182	-0.028729	9.796424	0.048230	0.090331	-0.035306
+12.579101	0.016758	-0.043093	9.746149	0.046231	0.088599	-0.034240
+12.580039	0.033517	0.031123	9.741361	0.046098	0.084069	-0.033441
+12.581101	0.047881	-0.028729	9.722208	0.049029	0.086734	-0.032508
+12.582101	0.009576	-0.050275	9.755725	0.047297	0.090064	-0.035972
+12.583068	0.028729	0.016758	9.829940	0.045832	0.086600	-0.037571
+12.584098	0.038305	-0.007182	9.770089	0.047697	0.086334	-0.037971
+12.585100	0.062245	-0.076609	9.786848	0.049828	0.087266	-0.035706
+12.586103	0.071821	-0.059851	9.808394	0.047697	0.087133	-0.033441
+12.587099	-0.009576	0.011970	9.815576	0.047830	0.087933	-0.032508
+12.588099	0.007182	-0.019152	9.779666	0.048363	0.088732	-0.036372
+12.589058	0.016758	-0.011970	9.738967	0.048896	0.087133	-0.039170
+12.590101	0.050275	0.016758	9.679116	0.048096	0.087799	-0.038504
+12.591099	0.004788	-0.035911	9.707844	0.047830	0.088599	-0.037704
+12.592085	-0.011970	0.016758	9.707844	0.045299	0.088199	-0.036372
+12.593058	0.014364	-0.033517	9.753331	0.046897	0.088599	-0.034907
+12.594130	0.014364	-0.045487	9.810788	0.049162	0.088066	-0.036239
+12.595039	0.038305	0.002394	9.786848	0.046364	0.088199	-0.040902
+12.596073	0.009576	-0.004788	9.782060	0.044766	0.090064	-0.040769
+12.597101	-0.002394	-0.009576	9.765301	0.045965	0.085401	-0.041701
+12.598100	0.026334	-0.023940	9.794030	0.046231	0.085668	-0.037571
+12.599038	-0.009576	-0.019152	9.755725	0.047564	0.087666	-0.033974
+12.600084	-0.002394	0.014364	9.841911	0.047697	0.087933	-0.032775
+12.601105	-0.007182	-0.014364	9.880215	0.048363	0.088466	-0.035706
+12.602058	0.031123	-0.009576	9.858669	0.048363	0.088998	-0.035440
+12.603099	0.040699	-0.016758	9.858669	0.045832	0.093262	-0.037172
+12.604058	0.026334	-0.009576	9.762907	0.046098	0.090864	-0.036106
+12.605096	0.043093	0.028729	9.743755	0.047697	0.085668	-0.031842
+12.606104	0.026334	0.009576	9.777271	0.049296	0.085801	-0.036905
+12.607098	0.035911	-0.026334	9.846699	0.050228	0.087666	-0.040902
+12.608100	0.019152	-0.028729	9.851487	0.045698	0.088466	-0.038770
+12.609100	0.021546	-0.009576	9.808394	0.045299	0.088332	-0.036639
+12.610063	0.035911	0.028729	9.794030	0.047031	0.087400	-0.034907
+12.611099	0.000000	0.059851	9.798818	0.048629	0.085934	-0.037172
+12.612099	0.011970	-0.028729	9.820364	0.049029	0.088199	-0.036239
+12.613099	-0.007182	0.009576	9.794030	0.049962	0.089798	-0.034374
+12.614044	-0.040699	0.014364	9.724603	0.048496	0.088732	-0.034773
+12.615034	0.016758	0.019152	9.808394	0.046764	0.087400	-0.033041
+12.616081	-0.002394	-0.028729	9.798818	0.045032	0.087133	-0.031443
+12.617053	0.031123	-0.057457	9.877821	0.046498	0.088865	-0.036239
+12.618102	0.002394	-0.035911	9.880215	0.047963	0.087666	-0.038104
+12.619060	0.028729	-0.074215	9.784454	0.046631	0.085934	-0.036772
+12.620051	0.035911	-0.074215	9.810788	0.048763	0.088466	-0.035573
+12.621099	0.050275	-0.002394	9.784454	0.048363	0.089132	-0.036106
+12.622100	0.040699	0.031123	9.841911	0.045832	0.087266	-0.034240
+12.623100	0.038305	0.000000	9.801212	0.045832	0.083669	-0.033441
+12.624108	0.028729	0.038305	9.846699	0.046364	0.083669	-0.036505
+12.625079	0.016758	0.019152	9.861063	0.047830	0.087400	-0.037571
+12.626103	0.000000	-0.011970	9.774877	0.049429	0.087400	-0.036372
+12.627094	0.031123	0.004788	9.760513	0.047164	0.087400	-0.037438
+12.628100	0.052669	0.026334	9.748543	0.046498	0.088865	-0.039703
+12.629098	0.050275	-0.038305	9.782060	0.048496	0.085801	-0.037305
+12.630100	0.038305	-0.055063	9.851487	0.047963	0.085534	-0.035972
+12.631099	0.047881	-0.019152	9.853881	0.048230	0.087133	-0.038504
+12.632098	-0.031123	0.000000	9.820364	0.047031	0.085401	-0.037838
+12.633101	0.011970	-0.004788	9.774877	0.044632	0.088332	-0.038104
+12.634067	0.009576	-0.023940	9.779666	0.046364	0.088066	-0.039170
+12.635092	0.002394	-0.011970	9.791636	0.048096	0.087933	-0.035972
+12.636097	0.002394	-0.028729	9.815576	0.047697	0.084069	-0.037172
+12.637101	0.011970	-0.026334	9.803606	0.046098	0.085401	-0.033841
+12.638100	0.026334	-0.014364	9.887397	0.048230	0.087133	-0.034240
+12.639100	-0.038305	-0.033517	9.894580	0.049296	0.087666	-0.038904
+12.640099	-0.007182	-0.050275	9.801212	0.047164	0.090730	-0.038637
+12.641095	-0.050275	0.014364	9.674328	0.043700	0.088732	-0.037438
+12.642100	0.026334	0.011970	9.779666	0.045565	0.086334	-0.034240
+12.643081	0.019152	-0.011970	9.882609	0.045432	0.085668	-0.036505
+12.644073	-0.009576	-0.007182	9.937672	0.045832	0.087400	-0.039570
+12.645026	-0.009576	0.026334	9.904156	0.045565	0.088466	-0.038770
+12.646066	-0.035911	-0.019152	9.885003	0.047031	0.088998	-0.033574
+12.647127	-0.040699	0.028729	9.851487	0.044899	0.087799	-0.032242
+12.648099	-0.038305	0.067033	9.810788	0.044766	0.086201	-0.034107
+12.649100	0.023940	-0.007182	9.853881	0.048896	0.088865	-0.038371
+12.650069	0.038305	-0.031123	9.861063	0.048363	0.089132	-0.039037
+12.651090	0.038305	-0.050275	9.789242	0.044766	0.087933	-0.035173
+12.652043	0.069427	0.016758	9.722208	0.045565	0.088466	-0.035839
+12.653080	0.083792	0.021546	9.820364	0.047430	0.087133	-0.034773
+12.654100	0.057457	-0.038305	9.770089	0.045965	0.086201	-0.032109
+12.655098	0.088580	0.007182	9.817970	0.045965	0.085668	-0.032908
+12.656042	0.071821	0.023940	9.856275	0.046764	0.089132	-0.038637
+12.657101	0.069427	-0.035911	9.815576	0.049562	0.089132	-0.039570
+12.658103	0.076609	0.016758	9.834729	0.046631	0.088332	-0.036239
+12.659028	0.021546	-0.014364	9.827546	0.046364	0.087000	-0.033841
+12.660099	0.009576	-0.014364	9.839517	0.048230	0.087799	-0.035173
+12.661073	-0.007182	-0.016758	9.794030	0.048496	0.086334	-0.035839
+12.662103	-0.021546	-0.019152	9.832334	0.046364	0.084868	-0.036372
+12.663098	0.019152	-0.014364	9.844305	0.043034	0.085801	-0.035306
+12.664103	0.014364	-0.021546	9.851487	0.043433	0.087666	-0.038770
+12.665043	-0.007182	0.031123	9.863457	0.046098	0.090198	-0.036905
+12.666036	0.011970	-0.021546	9.798818	0.047963	0.091530	-0.033841
+12.667098	0.004788	-0.057457	9.765301	0.047031	0.088599	-0.034507
+12.668083	-0.019152	-0.043093	9.829940	0.047297	0.088466	-0.037305
+12.669099	-0.031123	-0.016758	9.798818	0.047830	0.089398	-0.037704
+12.670099	0.009576	0.009576	9.856275	0.048763	0.091530	-0.035972
+12.671098	0.033517	0.004788	9.825152	0.047963	0.091130	-0.035839
+12.672099	0.052669	-0.007182	9.806000	0.046764	0.087799	-0.036905
+12.673101	0.004788	-0.035911	9.772483	0.047031	0.089132	-0.037704
+12.674102	-0.004788	0.021546	9.827546	0.047830	0.088466	-0.037571
+12.675098	0.021546	0.016758	9.839517	0.046364	0.087133	-0.037172
+12.676061	0.016758	0.019152	9.815576	0.045299	0.085801	-0.036772
+12.677125	0.009576	0.000000	9.748543	0.047564	0.086467	-0.036372
+12.678103	-0.052669	-0.035911	9.748543	0.050628	0.087133	-0.039969
+12.679099	-0.028729	-0.033517	9.707844	0.047963	0.087266	-0.042634
+12.680098	0.021546	0.052669	9.779666	0.047031	0.088332	-0.040369
+12.681099	0.028729	0.000000	9.777271	0.045965	0.087799	-0.037838
+12.682103	0.021546	0.026334	9.815576	0.047564	0.087799	-0.034640
+12.683098	-0.016758	0.031123	9.767695	0.048230	0.089798	-0.035839
+12.684099	-0.035911	0.009576	9.750937	0.047031	0.090464	-0.038904
+12.685096	-0.023940	-0.016758	9.908944	0.047564	0.088599	-0.036239
+12.686058	-0.002394	0.004788	9.834729	0.047564	0.087933	-0.033175
+12.687098	-0.019152	0.016758	9.794030	0.045032	0.087000	-0.037305
+12.688093	-0.035911	-0.026334	9.810788	0.044233	0.088066	-0.039303
+12.689094	-0.040699	-0.038305	9.870639	0.046364	0.090198	-0.037838
+12.690092	-0.038305	-0.014364	9.849093	0.046498	0.089265	-0.034640
+12.691098	-0.014364	0.014364	9.873033	0.047963	0.087799	-0.037838
+12.692102	-0.028729	0.000000	9.846699	0.047297	0.088199	-0.037838
+12.693094	-0.038305	-0.014364	9.813182	0.047164	0.085534	-0.034773
+12.694097	0.014364	-0.038305	9.865851	0.045832	0.086067	-0.033841
+12.695042	-0.011970	-0.067033	9.760513	0.044233	0.087133	-0.032642
+12.696071	-0.014364	0.002394	9.798818	0.043833	0.088199	-0.034907
+12.697057	-0.040699	0.000000	9.851487	0.045432	0.086600	-0.039969
+12.698095	0.031123	-0.009576	9.803606	0.046897	0.089798	-0.036239
+12.699085	0.040699	0.052669	9.820364	0.048496	0.087933	-0.036639
+12.700096	0.047881	0.026334	9.837123	0.048496	0.086867	-0.037038
+12.701099	0.033517	-0.014364	9.832334	0.046897	0.087000	-0.037571
+12.702101	0.028729	0.007182	9.784454	0.047830	0.086734	-0.038371
+12.703101	0.059851	0.035911	9.765301	0.047963	0.087133	-0.039037
+12.704063	0.019152	0.014364	9.710238	0.046364	0.088066	-0.037571
+12.705060	0.019152	-0.050275	9.741361	0.045832	0.088332	-0.036905
+12.706102	-0.007182	0.002394	9.808394	0.047564	0.087666	-0.038770
+12.707050	0.004788	0.021546	9.801212	0.046498	0.087000	-0.040236
+12.708080	-0.014364	-0.033517	9.875427	0.045432	0.086867	-0.037971
+12.709099	-0.062245	-0.016758	9.863457	0.046764	0.088199	-0.037305
+12.710094	-0.011970	-0.019152	9.794030	0.045832	0.086334	-0.037971
+12.711098	0.038305	0.004788	9.829940	0.048230	0.087400	-0.039570
+12.712098	0.016758	-0.002394	9.837123	0.047031	0.089931	-0.038504
+12.713045	0.021546	-0.047881	9.856275	0.045299	0.090864	-0.033441
+12.714019	0.023940	-0.002394	9.806000	0.043700	0.088865	-0.034107
+12.715018	-0.021546	-0.014364	9.825152	0.045299	0.086867	-0.035972
+12.716022	-0.047881	0.004788	9.868245	0.047564	0.090730	-0.036905
+12.717023	0.000000	0.004788	9.829940	0.048763	0.091397	-0.037038
+12.718019	-0.009576	0.031123	9.794030	0.049828	0.087933	-0.035839
+12.719017	0.062245	-0.014364	9.837123	0.048363	0.084202	-0.035706
+12.720011	0.031123	0.009576	9.779666	0.047031	0.085401	-0.035972
+12.721024	0.023940	0.021546	9.738967	0.045965	0.087933	-0.035440
+12.722064	0.028729	0.031123	9.700662	0.045832	0.088998	-0.038637
+12.723077	-0.026334	0.064639	9.798818	0.046498	0.089665	-0.037838
+12.724072	-0.023940	0.059851	9.820364	0.047963	0.088998	-0.033574
+12.725078	-0.004788	-0.038305	9.808394	0.047697	0.087400	-0.035040
+12.726080	0.062245	-0.047881	9.734179	0.049429	0.085268	-0.036772
+12.727077	0.062245	-0.033517	9.738967	0.050228	0.086734	-0.037172
+12.728077	0.002394	-0.028729	9.755725	0.048629	0.087666	-0.036106
+12.729065	-0.002394	0.011970	9.858669	0.048629	0.087799	-0.035573
+12.730078	0.019152	-0.019152	9.892186	0.047430	0.087400	-0.037038
+12.731077	-0.031123	-0.016758	9.832334	0.047830	0.088599	-0.033574
+12.732055	0.007182	-0.004788	9.825152	0.047430	0.087400	-0.034773
+12.733077	0.038305	-0.055063	9.834729	0.048096	0.087133	-0.038104
+12.734008	0.009576	0.004788	9.806000	0.047430	0.088599	-0.036772
+12.735008	0.026334	0.000000	9.755725	0.048896	0.089265	-0.041035
+12.736020	0.064639	-0.016758	9.729391	0.045565	0.087933	-0.039037
+12.737013	0.047881	-0.028729	9.779666	0.045565	0.086600	-0.035839
+12.737989	0.026334	-0.040699	9.789242	0.048496	0.086201	-0.033441
+12.739011	0.050275	0.002394	9.760513	0.048363	0.087266	-0.033708
+12.740011	-0.021546	0.028729	9.726997	0.046631	0.089132	-0.034507
+12.741011	-0.021546	0.019152	9.837123	0.046498	0.090464	-0.036106
+12.742006	-0.031123	-0.004788	9.846699	0.046498	0.088998	-0.033841
+12.743011	0.000000	0.028729	9.810788	0.049962	0.087133	-0.034240
+12.744011	-0.014364	-0.014364	9.794030	0.048763	0.087400	-0.035440
+12.745008	-0.014364	0.000000	9.827546	0.047031	0.088865	-0.035306
+12.746022	0.033517	-0.016758	9.794030	0.046498	0.088199	-0.035306
+12.747014	-0.021546	-0.014364	9.825152	0.046498	0.089798	-0.034773
+12.748016	-0.004788	0.009576	9.901762	0.046231	0.088998	-0.033708
+12.749016	-0.007182	-0.009576	9.791636	0.046897	0.088865	-0.034240
+12.750021	-0.019152	-0.055063	9.762907	0.045832	0.092063	-0.036106
+12.751020	0.021546	-0.016758	9.861063	0.046764	0.091130	-0.037704
+12.752021	0.062245	0.019152	9.817970	0.049828	0.089265	-0.039037
+12.753017	0.028729	0.028729	9.810788	0.050894	0.086600	-0.037971
+12.754002	-0.059851	0.000000	9.789242	0.049695	0.087400	-0.036772
+12.755002	-0.007182	-0.016758	9.849093	0.046897	0.088599	-0.036905
+12.756000	-0.028729	-0.019152	9.837123	0.045832	0.088865	-0.037704
+12.757015	-0.014364	0.007182	9.801212	0.045565	0.089665	-0.036239
+12.758021	-0.002394	0.028729	9.786848	0.045965	0.087666	-0.039037
+12.759025	0.000000	0.002394	9.789242	0.046231	0.087133	-0.039836
+12.760025	-0.004788	-0.016758	9.825152	0.045698	0.086467	-0.035706
+12.761022	-0.007182	-0.038305	9.765301	0.045432	0.087533	-0.033841
+12.762021	-0.019152	-0.050275	9.798818	0.045698	0.087799	-0.034773
+12.763024	0.011970	-0.028729	9.796424	0.046764	0.088466	-0.038504
+12.764024	0.026334	-0.002394	9.767695	0.048896	0.088199	-0.037438
+12.765016	0.011970	0.040699	9.762907	0.048230	0.087533	-0.036372
+12.766021	0.055063	-0.019152	9.803606	0.048363	0.086201	-0.034773
+12.767026	-0.004788	-0.038305	9.755725	0.050095	0.086334	-0.035040
+12.768010	-0.031123	-0.045487	9.834729	0.048896	0.086600	-0.032908
+12.769019	-0.019152	-0.007182	9.794030	0.047297	0.088199	-0.036372
+12.770024	0.002394	-0.011970	9.817970	0.047031	0.087799	-0.038237
+12.771022	-0.035911	0.011970	9.834729	0.044766	0.086734	-0.037438
+12.772022	0.028729	-0.038305	9.765301	0.044632	0.085934	-0.035040
+12.773021	0.045487	0.007182	9.801212	0.045565	0.085801	-0.036106
+12.774023	-0.016758	0.021546	9.803606	0.046897	0.085934	-0.039969
+12.775018	-0.011970	0.019152	9.904156	0.048496	0.087000	-0.038371
+12.776022	-0.019152	0.028729	9.731785	0.049162	0.089398	-0.035839
+12.777024	-0.033517	-0.014364	9.789242	0.048496	0.090064	-0.038104
+12.778022	0.019152	-0.045487	9.782060	0.047564	0.088332	-0.036372
+12.779008	-0.007182	-0.035911	9.762907	0.046764	0.086734	-0.040636
+12.780018	-0.004788	-0.083792	9.820364	0.046231	0.084469	-0.039836
+12.781021	0.007182	-0.007182	9.841911	0.047031	0.085135	-0.033841
+12.782010	0.033517	0.002394	9.834729	0.047830	0.086734	-0.033841
+12.783011	0.011970	0.014364	9.736573	0.049962	0.088466	-0.038371
+12.784013	0.023940	-0.021546	9.791636	0.047430	0.089531	-0.041035
+12.785036	0.019152	0.023940	9.918520	0.046631	0.088332	-0.039170
+12.786041	-0.019152	0.021546	9.851487	0.046897	0.088865	-0.035972
+12.787085	-0.016758	0.021546	9.846699	0.046098	0.089931	-0.035839
+12.788090	0.059851	-0.014364	9.849093	0.047031	0.089265	-0.036639
+12.789068	0.088580	0.004788	9.868245	0.047830	0.089265	-0.038104
+12.790071	0.014364	0.004788	9.779666	0.046631	0.089798	-0.039570
+12.791086	0.014364	-0.016758	9.715026	0.044100	0.087400	-0.038770
+12.792088	0.112520	0.002394	9.707844	0.043700	0.086734	-0.040369
+12.793050	0.016758	-0.009576	9.734179	0.047297	0.087000	-0.040502
+12.794092	0.004788	-0.045487	9.846699	0.046897	0.088332	-0.038104
+12.795026	-0.019152	-0.043093	9.877821	0.045432	0.087799	-0.035440
+12.796089	-0.004788	0.004788	9.791636	0.044499	0.087799	-0.034107
+12.797090	0.014364	0.057457	9.841911	0.045698	0.087533	-0.036639
+12.798091	0.033517	0.016758	9.822758	0.046231	0.086467	-0.034907
+12.799090	0.009576	0.033517	9.877821	0.046897	0.087533	-0.033175
+12.800071	-0.019152	0.000000	9.849093	0.046231	0.091397	-0.034374
+12.801047	0.026334	-0.004788	9.892186	0.046231	0.090597	-0.036905
+12.802091	-0.007182	-0.045487	9.882609	0.047297	0.089665	-0.037038
+12.803090	-0.031123	-0.028729	9.839517	0.048763	0.085801	-0.032775
+12.804085	-0.011970	-0.028729	9.825152	0.046897	0.086600	-0.032242
+12.805091	0.009576	0.000000	9.786848	0.049162	0.086067	-0.037838
+12.806091	0.052669	0.033517	9.767695	0.047297	0.088732	-0.039836
+12.807032	0.035911	0.023940	9.810788	0.048230	0.089265	-0.037038
+12.808090	-0.033517	-0.004788	9.863457	0.047164	0.090331	-0.035173
+12.809085	0.028729	0.002394	9.856275	0.047031	0.088865	-0.036106
+12.810022	-0.014364	0.035911	9.791636	0.046098	0.088466	-0.031043
+12.811068	-0.004788	-0.021546	9.789242	0.046897	0.087933	-0.033175
+12.812092	-0.009576	0.019152	9.782060	0.045832	0.090464	-0.036372
+12.813091	0.028729	-0.023940	9.664751	0.045832	0.090198	-0.039170
+12.814083	-0.019152	-0.028729	9.703056	0.047031	0.087533	-0.039836
+12.815092	-0.031123	-0.023940	9.753331	0.046498	0.087000	-0.036372
+12.816050	-0.040699	-0.050275	9.782060	0.047297	0.088199	-0.033974
+12.817091	-0.007182	-0.074215	9.820364	0.047164	0.086334	-0.033308
+12.818079	0.040699	-0.102944	9.856275	0.046631	0.084735	-0.035173
+12.819089	0.007182	-0.004788	9.908944	0.045565	0.084202	-0.039303
+12.820090	0.062245	0.007182	9.827546	0.045832	0.087133	-0.039037
+12.821082	0.045487	-0.023940	9.906550	0.047564	0.090331	-0.036639
+12.822105	0.040699	0.038305	9.849093	0.045965	0.090064	-0.037305
+12.823085	-0.031123	0.043093	9.806000	0.048496	0.087400	-0.036905
+12.824090	0.002394	-0.009576	9.846699	0.047297	0.085534	-0.039170
+12.825091	0.000000	-0.033517	9.734179	0.045432	0.088599	-0.037971
+12.826092	-0.007182	-0.031123	9.777271	0.045565	0.092462	-0.032642
+12.827091	0.000000	-0.033517	9.753331	0.047963	0.092063	-0.031709
+12.828092	0.000000	-0.004788	9.837123	0.048230	0.088998	-0.036106
+12.829089	0.009576	0.002394	9.834729	0.046498	0.086467	-0.037305
+12.830092	0.028729	0.047881	9.837123	0.045698	0.088732	-0.036372
+12.831084	-0.028729	0.009576	9.820364	0.044366	0.088998	-0.035040
+12.832135	0.002394	0.062245	9.815576	0.046631	0.087266	-0.036239
+12.833122	0.019152	0.002394	9.865851	0.047164	0.088066	-0.037838
+12.834145	-0.007182	-0.031123	9.846699	0.048629	0.088332	-0.041701
+12.835139	-0.035911	-0.009576	9.868245	0.046897	0.090331	-0.037571
+12.836141	-0.035911	-0.050275	9.829940	0.045832	0.089265	-0.033708
+12.837140	0.040699	0.007182	9.846699	0.044366	0.089531	-0.033574
+12.838142	0.021546	0.004788	9.865851	0.044499	0.088599	-0.037172
+12.839109	0.007182	0.040699	9.837123	0.046631	0.089132	-0.038104
+12.840068	-0.028729	-0.016758	9.767695	0.048363	0.087799	-0.036772
+12.841143	0.000000	-0.038305	9.774877	0.046897	0.086334	-0.036639
+12.842143	0.033517	-0.038305	9.837123	0.043966	0.088066	-0.038504
+12.843089	0.062245	0.038305	9.820364	0.043300	0.091263	-0.036639
+12.844140	0.071821	0.021546	9.846699	0.046098	0.088066	-0.033441
+12.845117	0.002394	0.014364	9.791636	0.047963	0.084469	-0.034374
+12.846049	0.000000	0.026334	9.712632	0.048230	0.088199	-0.039836
+12.847140	-0.007182	0.035911	9.801212	0.049162	0.089931	-0.037438
+12.848140	-0.004788	-0.004788	9.794030	0.048096	0.088066	-0.036639
+12.849064	-0.023940	0.004788	9.817970	0.046631	0.086600	-0.034107
+12.850045	0.009576	-0.057457	9.817970	0.045832	0.088199	-0.031443
+12.851068	-0.011970	-0.021546	9.798818	0.046631	0.089665	-0.032775
+12.852098	0.045487	-0.004788	9.808394	0.048496	0.087666	-0.033974
+12.853142	0.052669	-0.028729	9.801212	0.048230	0.090997	-0.037438
+12.854144	-0.028729	-0.007182	9.789242	0.045299	0.089665	-0.041968
+12.855140	0.000000	-0.014364	9.777271	0.045032	0.088998	-0.038237
+12.856141	-0.011970	-0.045487	9.765301	0.044632	0.088732	-0.035173
+12.857118	0.009576	-0.023940	9.784454	0.045965	0.088732	-0.035440
+12.858065	0.055063	-0.069427	9.782060	0.047564	0.086600	-0.035306
+12.859139	0.033517	0.002394	9.784454	0.047430	0.087400	-0.037305
+12.860047	0.004788	0.035911	9.810788	0.047564	0.088732	-0.038104
+12.861137	0.023940	0.004788	9.841911	0.048763	0.087799	-0.035972
+12.862141	-0.021546	-0.047881	9.875427	0.049296	0.088332	-0.031842
+12.863141	-0.062245	-0.004788	9.846699	0.047564	0.089132	-0.031309
+12.864139	-0.009576	0.000000	9.832334	0.047164	0.088865	-0.035040
+12.865086	0.026334	-0.009576	9.801212	0.046897	0.089398	-0.037438
+12.866098	0.040699	-0.043093	9.691086	0.047564	0.088998	-0.037838
+12.867123	0.026334	-0.071821	9.688692	0.048096	0.087666	-0.037438
+12.868139	-0.004788	-0.002394	9.765301	0.046364	0.088599	-0.036505
+12.869080	0.023940	-0.045487	9.822758	0.045032	0.088732	-0.035306
+12.870113	0.043093	-0.040699	9.777271	0.045032	0.088199	-0.036239
+12.871140	0.033517	0.011970	9.779666	0.045165	0.084735	-0.036905
+12.872140	0.009576	0.038305	9.873033	0.047830	0.085801	-0.038770
+12.873115	0.069427	0.045487	9.827546	0.045698	0.086600	-0.037571
+12.874112	0.067033	-0.007182	9.798818	0.047297	0.087133	-0.035040
+12.875074	0.035911	-0.023940	9.834729	0.045299	0.088732	-0.035440
+12.876142	0.059851	0.002394	9.801212	0.043034	0.086734	-0.034107
+12.877139	0.019152	-0.028729	9.791636	0.044899	0.086734	-0.032375
+12.878143	-0.011970	0.033517	9.786848	0.046231	0.085534	-0.033041
+12.879138	-0.009576	0.040699	9.743755	0.044632	0.087266	-0.036239
+12.880076	-0.023940	-0.009576	9.767695	0.046231	0.088998	-0.035440
+12.881116	-0.038305	-0.014364	9.794030	0.047564	0.088066	-0.037438
+12.882141	0.009576	-0.007182	9.772483	0.047031	0.087799	-0.036639
+12.883085	0.067033	0.033517	9.887397	0.045965	0.086467	-0.034240
+12.884067	0.050275	0.064639	9.844305	0.045832	0.085268	-0.037172
+12.885061	0.040699	0.047881	9.779666	0.044632	0.086467	-0.035440
+12.886141	0.021546	0.028729	9.810788	0.045299	0.087666	-0.035972
+12.887141	-0.002394	-0.028729	9.820364	0.046364	0.085801	-0.036239
+12.888140	-0.021546	0.028729	9.896974	0.049162	0.086334	-0.037704
+12.889109	0.033517	0.021546	9.841911	0.049029	0.088599	-0.039436
+12.890144	-0.040699	0.031123	9.801212	0.045698	0.089265	-0.040502
+12.891101	-0.043093	0.038305	9.777271	0.044366	0.087666	-0.038770
+12.892138	0.016758	-0.038305	9.820364	0.046764	0.084602	-0.035839
+12.893084	-0.002394	0.016758	9.896974	0.048363	0.086467	-0.034907
+12.894143	-0.031123	0.021546	9.861063	0.047697	0.088199	-0.039037
+12.895138	-0.026334	-0.026334	9.779666	0.047430	0.088199	-0.039969
+12.896050	0.021546	-0.002394	9.794030	0.046231	0.085135	-0.037971
+12.897015	-0.004788	0.002394	9.726997	0.045698	0.084069	-0.036639
+12.898140	-0.031123	-0.019152	9.786848	0.047697	0.087533	-0.034507
+12.899079	0.028729	-0.033517	9.849093	0.049695	0.090331	-0.035573
+12.900118	0.043093	-0.059851	9.827546	0.050095	0.089798	-0.034773
+12.901077	-0.011970	-0.026334	9.841911	0.048230	0.090864	-0.037704
+12.902098	0.026334	0.014364	9.808394	0.046631	0.087933	-0.037704
+12.903111	0.026334	-0.002394	9.834729	0.045698	0.087133	-0.037571
+12.904137	0.043093	0.000000	9.837123	0.046231	0.086867	-0.037971
+12.905115	0.019152	0.004788	9.801212	0.048363	0.086467	-0.036772
+12.906142	-0.009576	0.002394	9.810788	0.047697	0.087666	-0.038237
+12.907115	0.007182	-0.040699	9.822758	0.045032	0.087400	-0.037172
+12.908139	0.035911	-0.011970	9.849093	0.044499	0.087799	-0.036905
+12.909139	0.050275	0.016758	9.806000	0.046498	0.086067	-0.035573
+12.910082	-0.016758	0.011970	9.798818	0.047031	0.086067	-0.036372
+12.911076	-0.047881	-0.014364	9.789242	0.047430	0.089132	-0.038371
+12.912140	0.016758	-0.002394	9.774877	0.047031	0.086867	-0.040502
+12.913115	-0.014364	-0.026334	9.810788	0.046631	0.086334	-0.037038
+12.914111	0.031123	-0.009576	9.825152	0.048763	0.085268	-0.036639
+12.915115	0.028729	0.011970	9.849093	0.048230	0.086600	-0.032775
+12.916138	-0.007182	-0.026334	9.808394	0.045299	0.088865	-0.031842
+12.917115	-0.050275	-0.035911	9.784454	0.047297	0.087000	-0.034640
+12.918082	0.002394	-0.007182	9.825152	0.046764	0.087933	-0.035706
+12.919049	0.031123	-0.002394	9.791636	0.046231	0.087400	-0.037971
+12.920049	-0.016758	-0.014364	9.808394	0.044366	0.088066	-0.040502
+12.921039	-0.016758	0.016758	9.765301	0.046631	0.090064	-0.040103
+12.922065	0.016758	0.021546	9.810788	0.047697	0.087533	-0.037172
+12.923075	0.016758	-0.002394	9.815576	0.047830	0.085002	-0.038104
+12.924074	0.050275	-0.035911	9.810788	0.048629	0.084602	-0.039436
+12.925074	0.038305	0.031123	9.734179	0.046098	0.086334	-0.037838
+12.926047	0.057457	0.023940	9.738967	0.045165	0.088599	-0.033708
+12.927027	0.023940	-0.009576	9.815576	0.047830	0.089132	-0.033175
+12.928087	0.026334	0.002394	9.868245	0.046631	0.085668	-0.036772
+12.929065	0.040699	0.011970	9.760513	0.045698	0.084202	-0.039570
+12.930065	0.002394	-0.021546	9.762907	0.045432	0.086201	-0.039037
+12.931042	0.026334	-0.055063	9.810788	0.047164	0.090064	-0.036505
+12.932085	0.043093	-0.002394	9.774877	0.047564	0.091930	-0.033841
+12.933063	0.007182	0.002394	9.777271	0.049296	0.088865	-0.039436
+12.934061	0.026334	-0.050275	9.904156	0.048096	0.087133	-0.043567
+12.935063	0.057457	-0.038305	9.873033	0.046764	0.085934	-0.037172
+12.936063	-0.011970	0.002394	9.741361	0.045565	0.087133	-0.036372
+12.937065	-0.023940	0.028729	9.717420	0.045432	0.088599	-0.038104
+12.938063	0.071821	-0.023940	9.820364	0.045698	0.089798	-0.038637
+12.939064	0.064639	0.004788	9.765301	0.046231	0.088466	-0.036505
+12.940064	-0.004788	0.007182	9.829940	0.046764	0.087799	-0.036106
+12.941016	0.007182	-0.067033	9.863457	0.047297	0.090464	-0.037305
+12.942063	-0.009576	-0.043093	9.796424	0.047297	0.089398	-0.039436
+12.943066	0.033517	-0.047881	9.777271	0.045965	0.087799	-0.038770
+12.944063	0.043093	0.023940	9.875427	0.046098	0.086334	-0.036106
+12.945064	0.040699	-0.009576	9.748543	0.046364	0.085002	-0.036106
+12.946042	0.052669	0.035911	9.820364	0.044366	0.086201	-0.032642
+12.947063	0.076609	0.098156	9.825152	0.044233	0.087533	-0.033841
+12.948065	0.026334	-0.004788	9.825152	0.049029	0.088998	-0.038904
+12.949065	-0.014364	-0.014364	9.844305	0.050228	0.087000	-0.035040
+12.950075	0.000000	0.038305	9.813182	0.049296	0.084335	-0.032642
+12.951051	-0.011970	0.040699	9.837123	0.048096	0.085002	-0.038104
+12.952032	-0.050275	0.035911	9.791636	0.047963	0.089265	-0.038770
+12.953126	-0.052669	0.031123	9.712632	0.050495	0.089265	-0.037971
+12.954061	-0.002394	0.007182	9.815576	0.048496	0.086867	-0.035306
+12.955058	0.016758	0.009576	9.784454	0.046897	0.085934	-0.035173
+12.956122	-0.004788	-0.038305	9.825152	0.047031	0.086467	-0.035440
+12.957123	-0.028729	0.050275	9.750937	0.047430	0.087933	-0.034107
+12.958126	-0.014364	0.007182	9.827546	0.045832	0.088732	-0.035440
+12.959125	0.016758	-0.057457	9.832334	0.048896	0.088199	-0.037971
+12.960053	0.009576	-0.011970	9.810788	0.050628	0.088332	-0.038904
+12.961122	-0.021546	-0.038305	9.741361	0.050628	0.089665	-0.040769
+12.962130	-0.023940	-0.007182	9.806000	0.047297	0.088732	-0.037438
+12.963122	0.011970	-0.019152	9.873033	0.045565	0.086734	-0.035972
+12.964120	0.004788	-0.009576	9.870639	0.045832	0.086067	-0.037172
+12.965123	-0.014364	0.040699	9.863457	0.047564	0.086467	-0.036239
+12.966030	0.019152	0.026334	9.786848	0.048763	0.087666	-0.035306
+12.967124	0.064639	-0.014364	9.779666	0.047297	0.087133	-0.036905
+12.968077	-0.002394	-0.028729	9.865851	0.046231	0.089931	-0.036106
+12.969086	-0.007182	0.000000	9.880215	0.044899	0.087400	-0.038904
+12.970044	0.016758	-0.043093	9.772483	0.047297	0.088998	-0.039037
+12.971089	0.019152	-0.052669	9.952037	0.044233	0.088732	-0.036372
+12.972120	0.055063	-0.045487	9.899368	0.044499	0.087666	-0.034773
+12.973121	0.007182	-0.009576	9.808394	0.045565	0.087000	-0.037305
+12.974063	-0.004788	0.016758	9.820364	0.045832	0.087266	-0.035573
+12.975064	0.000000	0.007182	9.765301	0.047430	0.088199	-0.032508
+12.976122	0.004788	-0.026334	9.794030	0.045965	0.089398	-0.034374
+12.977124	0.031123	-0.014364	9.813182	0.046897	0.088599	-0.037038
+12.978075	0.007182	-0.045487	9.782060	0.045832	0.087400	-0.037172
+12.979079	-0.047881	-0.021546	9.782060	0.046098	0.087266	-0.034640
+12.980057	0.057457	-0.011970	9.758119	0.046631	0.088332	-0.033841
+12.981121	0.052669	-0.026334	9.777271	0.045965	0.087533	-0.038371
+12.982125	0.067033	-0.004788	9.758119	0.044766	0.087133	-0.037438
+12.983121	0.000000	-0.004788	9.705450	0.045432	0.086467	-0.035706
+12.984122	0.016758	-0.016758	9.796424	0.045698	0.087133	-0.037438
+12.985064	0.031123	0.000000	9.803606	0.047963	0.089265	-0.038104
+12.986125	0.071821	0.000000	9.801212	0.047297	0.088599	-0.038371
+12.987076	0.052669	0.043093	9.789242	0.046897	0.086334	-0.037571
+12.988078	0.050275	0.031123	9.784454	0.045299	0.088466	-0.035573
+12.989108	0.033517	0.009576	9.777271	0.043700	0.090730	-0.035839
+12.990125	0.000000	-0.004788	9.810788	0.045965	0.089531	-0.035440
+12.991088	-0.002394	-0.009576	9.861063	0.049029	0.089665	-0.035839
+12.992122	0.014364	-0.004788	9.827546	0.048363	0.088599	-0.039037
+12.993122	0.040699	-0.033517	9.841911	0.048363	0.086467	-0.039703
+12.994074	0.033517	-0.009576	9.789242	0.048763	0.088199	-0.035440
+12.995122	0.028729	-0.016758	9.738967	0.047430	0.088066	-0.035040
+12.996058	0.040699	-0.090974	9.839517	0.046631	0.086734	-0.035839
+12.997077	0.040699	-0.028729	9.803606	0.046631	0.088466	-0.035040
+12.998123	0.031123	-0.076609	9.686298	0.044499	0.089398	-0.036505
+12.999121	-0.004788	-0.076609	9.750937	0.045299	0.090997	-0.037971
+13.000059	-0.031123	-0.011970	9.829940	0.046498	0.089665	-0.036772
+13.001106	-0.035911	-0.019152	9.827546	0.048096	0.088332	-0.037172
+13.002125	-0.009576	0.031123	9.825152	0.048763	0.088865	-0.040103
+13.003121	0.095762	-0.002394	9.853881	0.048896	0.089265	-0.035306
+13.004120	0.023940	-0.026334	9.868245	0.046897	0.086467	-0.031576
+13.005075	-0.040699	0.028729	9.853881	0.046231	0.085534	-0.031709
+13.006078	-0.028729	-0.021546	9.882609	0.046231	0.084335	-0.038904
+13.007126	-0.016758	0.014364	9.770089	0.045832	0.083802	-0.038504
+13.008122	-0.014364	0.016758	9.808394	0.045832	0.086867	-0.039170
+13.009096	-0.023940	-0.004788	9.827546	0.046364	0.086201	-0.038371
+13.010125	-0.023940	-0.031123	9.880215	0.045965	0.086600	-0.035040
+13.011122	0.062245	-0.016758	9.801212	0.046897	0.087666	-0.035173
+13.012120	0.026334	0.028729	9.762907	0.047830	0.088865	-0.037438
+13.013119	-0.035911	-0.002394	9.841911	0.048896	0.086867	-0.038637
+13.014063	-0.026334	0.031123	9.858669	0.048096	0.086067	-0.036372
+13.015087	0.009576	-0.002394	9.810788	0.046631	0.088066	-0.036905
+13.016047	0.004788	-0.016758	9.806000	0.045432	0.089665	-0.037305
+13.017056	-0.014364	0.016758	9.865851	0.045565	0.091530	-0.036772
+13.018033	-0.059851	0.009576	9.861063	0.047697	0.090597	-0.035706
+13.019120	-0.028729	0.021546	9.882609	0.047963	0.088066	-0.034240
+13.020107	0.021546	-0.086186	9.822758	0.046098	0.087666	-0.036905
+13.021076	0.002394	-0.040699	9.750937	0.046764	0.088599	-0.037172
+13.022125	-0.011970	-0.031123	9.738967	0.048629	0.088199	-0.038504
+13.023131	-0.007182	-0.038305	9.791636	0.049029	0.087266	-0.037172
+13.024057	0.000000	0.028729	9.829940	0.049162	0.086600	-0.037971
+13.025067	0.019152	-0.009576	9.803606	0.047297	0.088732	-0.034507
+13.026124	0.052669	-0.023940	9.803606	0.045032	0.087533	-0.035972
+13.027121	0.026334	-0.028729	9.777271	0.045165	0.085401	-0.038237
+13.028121	-0.014364	-0.028729	9.813182	0.047564	0.085934	-0.036772
+13.029120	0.000000	0.023940	9.779666	0.048230	0.087266	-0.036639
+13.030088	0.047881	0.050275	9.810788	0.046764	0.090064	-0.035972
+13.031120	-0.004788	-0.023940	9.803606	0.045565	0.086867	-0.035306
+13.032125	-0.031123	-0.035911	9.856275	0.045832	0.085801	-0.031443
+13.033080	-0.028729	-0.016758	9.794030	0.045165	0.088732	-0.037571
+13.034067	-0.014364	-0.047881	9.736573	0.044632	0.088332	-0.040769
+13.035089	0.023940	0.026334	9.853881	0.045299	0.087133	-0.035573
+13.036120	0.043093	0.052669	9.829940	0.048363	0.086467	-0.032775
+13.037120	0.064639	0.009576	9.875427	0.048896	0.085135	-0.035440
+13.038124	0.000000	-0.052669	9.810788	0.047564	0.085135	-0.039170
+13.039122	-0.045487	-0.016758	9.829940	0.046631	0.086734	-0.038904
+13.040075	-0.019152	0.043093	9.853881	0.048363	0.087133	-0.035440
+13.041121	-0.007182	0.040699	9.767695	0.048230	0.089265	-0.034773
+13.042077	-0.043093	-0.026334	9.820364	0.044899	0.091263	-0.031842
+13.043112	-0.045487	-0.045487	9.863457	0.047697	0.090331	-0.035306
+13.044045	0.002394	0.004788	9.765301	0.047031	0.089265	-0.036505
+13.045050	0.043093	0.009576	9.712632	0.046897	0.088998	-0.037438
+13.046056	0.007182	0.023940	9.741361	0.047830	0.089531	-0.036772
+13.047055	0.035911	-0.019152	9.844305	0.045965	0.090597	-0.033974
+13.048121	0.014364	-0.021546	9.822758	0.045698	0.087400	-0.035839
+13.049120	-0.023940	0.021546	9.789242	0.046231	0.087133	-0.036372
+13.050124	-0.011970	-0.019152	9.789242	0.047031	0.087133	-0.037172
+13.051009	0.002394	-0.023940	9.825152	0.047297	0.086734	-0.037438
+13.052048	-0.004788	0.000000	9.825152	0.045165	0.088732	-0.035573
+13.053110	0.026334	0.021546	9.801212	0.045299	0.086600	-0.033708
+13.054125	0.007182	-0.011970	9.738967	0.047297	0.086867	-0.033974
+13.055120	-0.007182	0.009576	9.700662	0.048096	0.088066	-0.034640
+13.056120	-0.011970	-0.021546	9.832334	0.047430	0.090331	-0.035706
+13.057123	0.021546	-0.057457	9.777271	0.047564	0.088732	-0.036772
+13.058122	0.043093	0.011970	9.777271	0.046897	0.085668	-0.038237
+13.059120	0.016758	0.009576	9.825152	0.044632	0.087533	-0.037038
+13.060073	0.050275	0.002394	9.822758	0.043966	0.088998	-0.033708
+13.061057	0.050275	-0.057457	9.789242	0.045965	0.088599	-0.035306
+13.062107	0.026334	-0.062245	9.715026	0.047830	0.089798	-0.034907
+13.063120	-0.045487	-0.035911	9.803606	0.046897	0.090597	-0.036772
+13.064077	0.007182	-0.014364	9.755725	0.046098	0.090997	-0.038770
+13.065093	0.038305	-0.026334	9.822758	0.045565	0.089665	-0.036905
+13.066054	-0.019152	-0.009576	9.772483	0.047963	0.088066	-0.034640
+13.067052	0.007182	-0.009576	9.748543	0.048763	0.088732	-0.035839
+13.068047	0.028729	-0.028729	9.806000	0.046897	0.088066	-0.034507
+13.069120	0.023940	-0.014364	9.829940	0.047697	0.089398	-0.032775
+13.070124	0.016758	-0.047881	9.815576	0.045565	0.091397	-0.034640
+13.071063	-0.004788	-0.076609	9.839517	0.045299	0.088199	-0.038770
+13.072109	-0.026334	0.002394	9.856275	0.047697	0.087266	-0.038104
+13.073121	0.016758	-0.026334	9.873033	0.047564	0.091130	-0.038637
+13.074121	0.050275	0.019152	9.870639	0.047564	0.089931	-0.039703
+13.075120	0.069427	0.031123	9.894580	0.046764	0.087533	-0.036106
+13.076076	0.021546	-0.055063	9.887397	0.046764	0.085668	-0.035440
+13.077122	-0.031123	-0.064639	9.851487	0.047031	0.087533	-0.033708
+13.078123	0.007182	0.000000	9.849093	0.046231	0.087400	-0.033441
+13.079124	0.038305	-0.016758	9.875427	0.046764	0.086867	-0.034640
+13.080071	-0.019152	-0.047881	9.861063	0.046897	0.088066	-0.037038
+13.081076	-0.064639	0.009576	9.858669	0.047164	0.086334	-0.041035
+13.082125	0.009576	-0.035911	9.806000	0.047830	0.086467	-0.038371
+13.083121	0.057457	-0.009576	9.815576	0.047430	0.086734	-0.035173
+13.084047	0.038305	-0.011970	9.892186	0.046231	0.087133	-0.036905
+13.085052	0.033517	-0.021546	9.894580	0.043567	0.085002	-0.035972
+13.086122	-0.007182	0.035911	9.753331	0.045299	0.084069	-0.035706
+13.087119	-0.002394	0.033517	9.820364	0.045299	0.082470	-0.037571
+13.088120	0.062245	-0.040699	9.868245	0.045565	0.083936	-0.035440
+13.089086	0.000000	0.016758	9.839517	0.045965	0.088199	-0.036505
+13.090061	-0.014364	0.004788	9.782060	0.045565	0.089398	-0.037971
+13.091124	0.000000	0.002394	9.767695	0.045965	0.089398	-0.036905
+13.092120	0.026334	0.031123	9.770089	0.045832	0.089132	-0.035440
+13.093120	0.033517	0.002394	9.875427	0.047031	0.089132	-0.034107
+13.094123	0.045487	0.059851	9.820364	0.047031	0.088466	-0.033708
+13.095118	0.062245	-0.009576	9.841911	0.046231	0.087799	-0.035573
+13.096058	0.045487	-0.011970	9.789242	0.047031	0.088332	-0.033974
+13.097027	-0.021546	-0.014364	9.856275	0.047697	0.089798	-0.038237
+13.098123	-0.002394	0.004788	9.873033	0.046098	0.090730	-0.039037
+13.099073	0.016758	0.009576	9.841911	0.047430	0.088599	-0.041835
+13.100052	0.011970	-0.028729	9.798818	0.046897	0.088998	-0.039303
+13.101103	0.019152	-0.031123	9.806000	0.047697	0.089798	-0.034640
+13.102124	0.071821	-0.045487	9.784454	0.046631	0.086201	-0.037438
+13.103118	0.052669	0.045487	9.784454	0.043833	0.085934	-0.037172
+13.104117	0.035911	0.026334	9.863457	0.045698	0.086734	-0.031576
+13.105122	-0.002394	-0.031123	9.829940	0.045965	0.088732	-0.030910
+13.106126	-0.009576	-0.011970	9.806000	0.045698	0.086600	-0.031975
+13.107120	-0.016758	-0.023940	9.839517	0.047164	0.086467	-0.034507
+13.108074	-0.014364	-0.033517	9.803606	0.045299	0.087533	-0.037038
+13.109093	0.019152	0.028729	9.801212	0.045565	0.088332	-0.039703
+13.110119	0.050275	0.009576	9.894580	0.045165	0.086201	-0.038904
+13.111120	0.023940	-0.002394	9.887397	0.045965	0.083536	-0.034907
+13.112118	-0.019152	-0.033517	9.762907	0.045965	0.084602	-0.031975
+13.113124	0.035911	-0.023940	9.722208	0.045698	0.087266	-0.035972
+13.114123	0.028729	0.057457	9.810788	0.047430	0.088199	-0.038504
+13.115119	0.062245	0.026334	9.846699	0.046364	0.086734	-0.037571
+13.116077	0.009576	-0.038305	9.767695	0.048763	0.085801	-0.036372
+13.117062	0.004788	0.026334	9.782060	0.048096	0.084735	-0.036639
+13.118045	0.038305	0.009576	9.820364	0.046897	0.086067	-0.036239
+13.119076	-0.043093	0.000000	9.798818	0.044766	0.085401	-0.036239
+13.120074	0.004788	-0.081397	9.810788	0.045165	0.084735	-0.037305
+13.121121	0.021546	-0.067033	9.822758	0.044499	0.088998	-0.035706
+13.122124	-0.028729	0.002394	9.803606	0.045965	0.090464	-0.032242
+13.123118	-0.009576	0.038305	9.806000	0.049962	0.090597	-0.034374
+13.124119	0.031123	0.011970	9.798818	0.049962	0.088199	-0.037571
+13.125120	-0.014364	-0.040699	9.798818	0.048230	0.089265	-0.035440
+13.126074	0.021546	-0.021546	9.753331	0.044899	0.088732	-0.033708
+13.127074	0.009576	0.014364	9.786848	0.046897	0.084868	-0.036239
+13.128092	0.055063	-0.019152	9.817970	0.048896	0.085401	-0.037438
+13.129076	0.062245	0.000000	9.810788	0.046764	0.085801	-0.037305
+13.130123	0.021546	0.026334	9.803606	0.046098	0.089132	-0.037704
+13.131118	0.038305	-0.033517	9.846699	0.046498	0.089265	-0.036239
+13.132121	0.016758	-0.040699	9.815576	0.047564	0.086867	-0.034773
+13.133119	-0.004788	-0.023940	9.772483	0.047963	0.086867	-0.037571
+13.134051	0.002394	-0.026334	9.767695	0.048763	0.084602	-0.036505
+13.135061	-0.016758	-0.047881	9.870639	0.048896	0.084602	-0.037305
+13.136073	0.004788	-0.021546	9.846699	0.048096	0.087533	-0.036639
+13.137091	0.009576	-0.040699	9.784454	0.049296	0.088332	-0.036905
+13.138129	0.047881	-0.028729	9.760513	0.049962	0.090198	-0.039037
+13.139118	0.028729	-0.043093	9.774877	0.048363	0.091530	-0.037038
+13.140072	0.047881	-0.009576	9.748543	0.046098	0.087533	-0.037038
+13.141119	0.076609	-0.014364	9.894580	0.044632	0.084602	-0.035306
+13.142124	0.033517	-0.016758	9.837123	0.044233	0.085934	-0.032375
+13.143119	0.047881	-0.040699	9.794030	0.044899	0.087799	-0.034374
+13.144079	0.026334	-0.019152	9.731785	0.044233	0.089665	-0.037838
+13.145052	0.004788	-0.067033	9.803606	0.046631	0.087266	-0.037838
+13.146078	0.009576	-0.033517	9.806000	0.048629	0.086600	-0.039170
+13.147038	0.026334	0.007182	9.815576	0.050628	0.086734	-0.035972
+13.148117	0.016758	-0.014364	9.741361	0.049828	0.087000	-0.034640
+13.149119	0.000000	0.021546	9.798818	0.046498	0.086867	-0.034107
+13.150077	-0.002394	0.021546	9.803606	0.044766	0.089265	-0.033574
+13.151119	0.007182	-0.002394	9.794030	0.045965	0.089132	-0.033308
+13.152072	0.026334	0.007182	9.806000	0.049029	0.088332	-0.034507
+13.153081	0.016758	-0.011970	9.827546	0.049429	0.088732	-0.035440
+13.154076	0.028729	-0.011970	9.810788	0.048629	0.086201	-0.034640
+13.155111	0.093368	0.002394	9.777271	0.047164	0.086467	-0.032642
+13.156122	0.045487	0.023940	9.839517	0.048096	0.087799	-0.033308
+13.157118	-0.026334	0.026334	9.844305	0.050361	0.087666	-0.033175
+13.158123	-0.002394	0.031123	9.827546	0.048896	0.088732	-0.032642
+13.159121	-0.009576	-0.057457	9.832334	0.047430	0.087000	-0.037305
+13.160120	0.033517	-0.004788	9.734179	0.045965	0.086867	-0.035972
+13.161123	-0.004788	0.026334	9.743755	0.044499	0.087400	-0.030776
+13.162124	-0.011970	0.067033	9.794030	0.043567	0.087933	-0.033974
+13.163069	-0.002394	0.007182	9.870639	0.044366	0.086334	-0.036372
+13.164107	0.055063	-0.033517	9.844305	0.047297	0.086067	-0.038637
+13.165069	0.040699	-0.014364	9.741361	0.048496	0.088199	-0.035972
+13.166041	0.026334	-0.031123	9.726997	0.049162	0.090064	-0.036106
+13.167117	0.021546	-0.019152	9.750937	0.046098	0.091530	-0.037838
+13.168050	-0.004788	0.002394	9.724603	0.044899	0.090597	-0.034374
+13.169118	0.028729	-0.002394	9.863457	0.044766	0.088332	-0.033574
+13.170074	0.047881	0.000000	9.791636	0.047963	0.087266	-0.035306
+13.171117	0.059851	0.014364	9.832334	0.048230	0.089265	-0.036505
+13.172074	0.000000	0.004788	9.837123	0.049695	0.089132	-0.036372
+13.173115	-0.007182	0.064639	9.765301	0.050628	0.087133	-0.037838
+13.174122	0.016758	0.033517	9.791636	0.049562	0.086600	-0.040902
+13.175119	0.000000	-0.011970	9.798818	0.047164	0.086334	-0.036639
+13.176120	-0.016758	0.002394	9.762907	0.045965	0.087666	-0.037038
+13.177079	0.031123	0.002394	9.774877	0.046897	0.089132	-0.038104
+13.178119	0.021546	-0.023940	9.703056	0.049695	0.087799	-0.038504
+13.179118	0.011970	-0.038305	9.789242	0.048763	0.086867	-0.036372
+13.180051	-0.011970	0.000000	9.822758	0.045965	0.088466	-0.036372
+13.181117	-0.023940	0.040699	9.913732	0.044366	0.089398	-0.034507
+13.182054	0.055063	0.000000	9.825152	0.046631	0.090331	-0.036505
+13.183117	0.043093	-0.038305	9.786848	0.047564	0.088732	-0.038770
+13.184094	-0.009576	0.021546	9.803606	0.047963	0.086201	-0.036772
+13.185065	0.040699	0.031123	9.849093	0.046764	0.084469	-0.033041
+13.186120	0.067033	0.021546	9.868245	0.048629	0.088466	-0.033708
+13.187118	0.069427	0.050275	9.851487	0.049162	0.090064	-0.037838
+13.188118	0.045487	0.011970	9.820364	0.047830	0.088466	-0.037038
+13.189071	-0.004788	-0.045487	9.861063	0.047963	0.088199	-0.034773
+13.190031	0.009576	-0.035911	9.853881	0.048363	0.087133	-0.033974
+13.191114	0.031123	0.011970	9.767695	0.047697	0.086067	-0.036239
+13.192119	-0.014364	-0.021546	9.717420	0.045165	0.084868	-0.038504
+13.193120	-0.002394	0.016758	9.760513	0.047564	0.084202	-0.039836
+13.194075	0.035911	-0.047881	9.844305	0.046764	0.086867	-0.035440
+13.195118	0.055063	-0.038305	9.844305	0.045965	0.087400	-0.031842
+13.196117	0.028729	-0.050275	9.798818	0.047830	0.087266	-0.032908
+13.197016	-0.016758	-0.031123	9.813182	0.049296	0.086734	-0.036106
+13.198046	0.045487	0.002394	9.849093	0.049029	0.084868	-0.037038
+13.199073	0.057457	0.028729	9.813182	0.045565	0.087533	-0.035440
+13.200054	-0.019152	0.002394	9.786848	0.045165	0.087533	-0.034640
+13.201124	0.009576	-0.007182	9.873033	0.047430	0.086467	-0.033974
+13.202051	-0.004788	0.004788	9.808394	0.049296	0.086867	-0.036106
+13.203119	0.047881	-0.047881	9.820364	0.047697	0.086467	-0.036372
+13.204117	0.076609	-0.081397	9.810788	0.045832	0.088066	-0.034507
+13.205118	0.052669	-0.052669	9.743755	0.046098	0.087000	-0.033175
+13.206122	0.040699	-0.019152	9.817970	0.046498	0.086467	-0.035972
+13.207118	0.011970	0.023940	9.813182	0.048896	0.087666	-0.037438
+13.208073	0.062245	0.028729	9.798818	0.048230	0.089665	-0.035440
+13.209093	0.028729	0.011970	9.849093	0.047830	0.088199	-0.035839
+13.210047	0.033517	0.014364	9.813182	0.047963	0.088865	-0.037172
+13.211118	-0.007182	0.019152	9.734179	0.045832	0.090198	-0.037838
+13.212119	-0.014364	0.004788	9.760513	0.046364	0.090064	-0.038237
+13.213120	-0.004788	0.004788	9.882609	0.046364	0.088199	-0.035573
+13.214120	0.035911	-0.004788	9.865851	0.047430	0.085801	-0.035040
+13.215074	0.069427	0.002394	9.820364	0.046764	0.084602	-0.036639
+13.216069	0.033517	-0.021546	9.827546	0.043167	0.088865	-0.035839
+13.217017	0.023940	-0.019152	9.839517	0.045565	0.088998	-0.038637
+13.218085	0.067033	0.007182	9.892186	0.047164	0.086201	-0.038504
+13.219072	0.038305	0.014364	9.827546	0.047830	0.087000	-0.036905
+13.220057	-0.038305	0.009576	9.765301	0.047697	0.088732	-0.035839
+13.221118	0.007182	0.016758	9.758119	0.047031	0.087533	-0.034507
+13.222122	-0.016758	-0.016758	9.829940	0.047564	0.088066	-0.035306
+13.223117	0.014364	0.045487	9.822758	0.048096	0.089132	-0.038237
+13.224116	0.014364	0.016758	9.789242	0.043567	0.089531	-0.035706
+13.225057	0.028729	0.007182	9.813182	0.046897	0.089132	-0.033574
+13.226069	0.014364	0.040699	9.777271	0.049029	0.090331	-0.035972
+13.227110	-0.014364	-0.007182	9.839517	0.048363	0.089265	-0.036905
+13.228118	-0.052669	-0.023940	9.794030	0.046897	0.085401	-0.034907
+13.229116	-0.009576	0.004788	9.815576	0.044899	0.086067	-0.034640
+13.230093	-0.040699	0.007182	9.806000	0.044100	0.089931	-0.035839
+13.231118	-0.011970	-0.019152	9.724603	0.044899	0.086600	-0.038104
+13.232118	0.000000	-0.019152	9.738967	0.046231	0.086600	-0.036639
+13.233060	-0.021546	0.009576	9.791636	0.045698	0.087133	-0.035706
+13.234024	-0.026334	0.059851	9.803606	0.046364	0.089665	-0.036639
+13.235048	-0.011970	0.031123	9.801212	0.049695	0.090198	-0.035573
+13.236092	0.011970	-0.016758	9.822758	0.048629	0.088732	-0.035706
+13.237119	0.009576	-0.011970	9.726997	0.047697	0.088466	-0.039436
+13.238073	-0.028729	-0.009576	9.755725	0.046897	0.088998	-0.040236
+13.239060	-0.016758	-0.016758	9.777271	0.047430	0.089265	-0.038371
+13.240076	0.031123	0.000000	9.817970	0.046631	0.087799	-0.031576
+13.241123	-0.004788	-0.007182	9.762907	0.044899	0.084868	-0.030776
+13.242124	-0.011970	-0.043093	9.782060	0.046098	0.086600	-0.031176
+13.243119	-0.004788	0.011970	9.770089	0.045432	0.088199	-0.034773
+13.244071	-0.011970	-0.023940	9.722208	0.045299	0.088865	-0.036505
+13.245071	-0.019152	-0.021546	9.770089	0.046764	0.088865	-0.034374
+13.246122	0.064639	0.011970	9.762907	0.046231	0.086334	-0.036772
+13.247057	0.045487	0.011970	9.767695	0.044632	0.086467	-0.038770
+13.248118	0.007182	0.009576	9.772483	0.045432	0.088332	-0.039037
+13.249119	0.023940	-0.016758	9.813182	0.048896	0.087799	-0.037438
+13.250049	0.014364	0.028729	9.858669	0.050361	0.087799	-0.035573
+13.251059	0.028729	-0.009576	9.770089	0.047564	0.087400	-0.038104
+13.252039	0.090974	-0.021546	9.829940	0.049029	0.088466	-0.037971
+13.253071	0.059851	-0.031123	9.873033	0.048096	0.087666	-0.036239
+13.254062	0.033517	-0.043093	9.846699	0.046231	0.087266	-0.032508
+13.255116	0.019152	0.038305	9.894580	0.044499	0.086201	-0.033708
+13.256117	0.067033	0.019152	9.832334	0.047031	0.085801	-0.036639
+13.257119	-0.009576	0.023940	9.750937	0.048096	0.088466	-0.037172
+13.258119	0.014364	0.002394	9.693480	0.047963	0.087933	-0.037305
+13.259058	0.035911	-0.019152	9.743755	0.046631	0.086067	-0.036505
+13.260025	0.019152	-0.033517	9.808394	0.045698	0.087666	-0.036505
+13.261234	0.011970	0.023940	9.667146	0.048230	0.088466	-0.036106
+13.262071	-0.050275	-0.038305	9.647993	0.046498	0.087933	-0.038904
+13.263076	0.000000	-0.043093	9.719814	0.045832	0.086334	-0.038237
+13.264120	0.031123	-0.014364	9.813182	0.047031	0.089931	-0.037571
+13.265064	-0.016758	0.023940	9.846699	0.047830	0.092329	-0.034773
+13.266056	0.009576	0.035911	9.782060	0.049162	0.089931	-0.035440
+13.267117	-0.002394	-0.031123	9.803606	0.049029	0.087933	-0.035706
+13.268054	-0.014364	0.023940	9.777271	0.046498	0.086334	-0.035573
+13.269117	0.040699	0.035911	9.817970	0.044632	0.087799	-0.033441
+13.270119	0.047881	0.002394	9.813182	0.044766	0.086334	-0.032908
+13.271071	0.007182	-0.011970	9.724603	0.045299	0.088332	-0.034907
+13.272110	-0.021546	-0.011970	9.755725	0.048230	0.090064	-0.035173
+13.273118	-0.009576	-0.026334	9.839517	0.050495	0.088466	-0.038104
+13.274088	-0.016758	-0.045487	9.834729	0.048896	0.087400	-0.041701
+13.275118	0.043093	0.050275	9.798818	0.045832	0.086867	-0.038504
+13.276118	0.043093	0.014364	9.798818	0.044766	0.086734	-0.035573
+13.277118	0.035911	-0.047881	9.837123	0.045299	0.086467	-0.034907
+13.278069	-0.021546	0.026334	9.794030	0.047031	0.087266	-0.036505
+13.279082	0.004788	0.069427	9.808394	0.047297	0.090198	-0.040236
+13.280071	0.052669	-0.011970	9.791636	0.047164	0.091130	-0.037838
+13.281111	0.028729	-0.014364	9.679116	0.048096	0.089931	-0.037305
+13.282122	0.026334	-0.009576	9.741361	0.047697	0.090464	-0.036239
+13.283118	0.000000	-0.019152	9.849093	0.045698	0.088732	-0.036106
+13.284118	-0.059851	-0.038305	9.794030	0.046098	0.088599	-0.034773
+13.285121	-0.004788	0.050275	9.736573	0.047430	0.087133	-0.034640
+13.286122	-0.031123	0.033517	9.753331	0.044366	0.084868	-0.035306
+13.287118	0.000000	-0.016758	9.834729	0.044366	0.087266	-0.035573
+13.288118	0.033517	-0.047881	9.813182	0.047430	0.088732	-0.037971
+13.289073	0.050275	-0.031123	9.822758	0.047697	0.088599	-0.037038
+13.290054	0.052669	-0.016758	9.865851	0.045565	0.087533	-0.036639
+13.291116	0.009576	-0.004788	9.719814	0.046631	0.085401	-0.037838
+13.292118	0.009576	-0.019152	9.779666	0.046631	0.084202	-0.035306
+13.293087	-0.007182	-0.002394	9.849093	0.047564	0.086201	-0.032109
+13.294056	-0.021546	-0.047881	9.870639	0.048763	0.089931	-0.032908
+13.295027	-0.014364	0.002394	9.782060	0.046897	0.089265	-0.035040
+13.296026	0.033517	-0.026334	9.782060	0.048363	0.088865	-0.035306
+13.297026	0.055063	0.004788	9.873033	0.048763	0.088599	-0.035972
+13.297971	0.050275	0.031123	9.791636	0.045698	0.088599	-0.036239
+13.299057	0.023940	0.004788	9.746149	0.046231	0.086067	-0.035839
+13.299984	-0.002394	-0.040699	9.784454	0.048096	0.088332	-0.039703
+13.301006	-0.011970	0.014364	9.806000	0.047697	0.090464	-0.038770
+13.301977	-0.002394	0.035911	9.803606	0.046231	0.088332	-0.032908
+13.302964	0.040699	-0.023940	9.849093	0.044632	0.087533	-0.032642
+13.304063	0.016758	-0.026334	9.896974	0.047297	0.086867	-0.035040
+13.305058	0.011970	-0.043093	9.765301	0.049962	0.088066	-0.039570
+13.306018	0.011970	-0.026334	9.738967	0.048496	0.089398	-0.039703
+13.307057	0.033517	0.000000	9.829940	0.044632	0.088732	-0.040103
+13.307994	0.038305	0.014364	9.827546	0.044100	0.086334	-0.040236
+13.308988	0.016758	0.028729	9.767695	0.046364	0.087933	-0.037971
+13.310001	-0.026334	-0.011970	9.640811	0.047031	0.089798	-0.036772
+13.311000	-0.004788	-0.050275	9.750937	0.047697	0.088998	-0.037571
+13.311994	-0.011970	-0.016758	9.825152	0.046364	0.088865	-0.037172
+13.312994	-0.026334	-0.002394	9.906550	0.043567	0.090331	-0.036372
+13.313979	0.069427	0.016758	9.863457	0.043833	0.090864	-0.036639
+13.314999	0.007182	0.007182	9.825152	0.045832	0.089931	-0.037038
+13.315996	0.011970	0.016758	9.753331	0.046631	0.088066	-0.034507
+13.317000	0.026334	0.007182	9.786848	0.048363	0.085801	-0.035040
+13.318000	-0.014364	-0.004788	9.786848	0.047697	0.087400	-0.038104
+13.318997	-0.019152	0.026334	9.688692	0.046897	0.088998	-0.036372
+13.319998	-0.002394	0.057457	9.724603	0.046631	0.087000	-0.037038
+13.320998	0.026334	0.045487	9.760513	0.048763	0.088732	-0.035706
+13.321968	0.064639	0.023940	9.789242	0.047297	0.088199	-0.034374
+13.322970	0.016758	-0.019152	9.865851	0.048496	0.087533	-0.037305
+13.323963	0.064639	0.000000	9.806000	0.049029	0.088998	-0.037571
+13.324963	0.071821	-0.062245	9.753331	0.049695	0.088066	-0.033974
+13.325963	0.023940	-0.014364	9.755725	0.048629	0.086334	-0.031309
+13.326988	0.019152	0.021546	9.762907	0.047564	0.088466	-0.033574
+13.327981	-0.026334	0.016758	9.803606	0.047297	0.090064	-0.034640
+13.329058	-0.026334	-0.016758	9.851487	0.047697	0.087799	-0.036772
+13.330059	0.011970	-0.011970	9.889792	0.048096	0.087133	-0.038237
+13.331056	-0.007182	-0.062245	9.851487	0.046897	0.085135	-0.038104
+13.332002	-0.009576	-0.047881	9.841911	0.047164	0.084868	-0.037971
+13.333056	0.007182	-0.038305	9.820364	0.047697	0.083136	-0.035573
+13.334042	0.031123	-0.019152	9.846699	0.047297	0.087666	-0.038237
+13.335058	0.050275	0.014364	9.798818	0.045698	0.087400	-0.039969
+13.336045	0.038305	-0.033517	9.798818	0.047031	0.087400	-0.041435
+13.337057	0.000000	-0.031123	9.889792	0.046498	0.087933	-0.038237
+13.338060	0.040699	-0.011970	9.834729	0.045432	0.087933	-0.036639
+13.339029	0.047881	0.028729	9.822758	0.045432	0.088599	-0.036372
+13.340017	0.000000	0.021546	9.832334	0.045698	0.087666	-0.036106
+13.341058	-0.007182	-0.014364	9.865851	0.047830	0.088599	-0.036239
+13.342058	0.031123	0.000000	9.794030	0.047830	0.087933	-0.035573
+13.343051	0.019152	-0.033517	9.801212	0.047830	0.088865	-0.038371
+13.344053	0.033517	-0.052669	9.870639	0.047031	0.088998	-0.038770
+13.345058	0.026334	-0.043093	9.746149	0.045432	0.091663	-0.034107
+13.346059	0.031123	-0.019152	9.839517	0.045432	0.092329	-0.032242
+13.347000	0.079003	-0.033517	9.863457	0.047164	0.091930	-0.035306
+13.348057	0.016758	-0.055063	9.851487	0.048363	0.092196	-0.035040
+13.349048	0.014364	-0.016758	9.825152	0.049695	0.088332	-0.034240
+13.349996	0.050275	-0.035911	9.841911	0.047031	0.086067	-0.034240
+13.350966	0.045487	-0.035911	9.817970	0.045165	0.087133	-0.033841
+13.351989	-0.014364	-0.002394	9.796424	0.042501	0.087266	-0.037172
+13.353059	-0.007182	0.038305	9.774877	0.043567	0.088332	-0.037971
+13.354058	-0.007182	0.007182	9.798818	0.047430	0.088732	-0.036772
+13.355057	0.014364	-0.033517	9.798818	0.048096	0.090064	-0.036639
+13.356058	0.043093	-0.038305	9.786848	0.047830	0.088732	-0.035306
+13.357058	-0.021546	0.014364	9.817970	0.047564	0.086467	-0.035440
+13.358058	-0.045487	-0.004788	9.885003	0.047164	0.089398	-0.034773
+13.359025	-0.028729	0.011970	9.861063	0.047564	0.090597	-0.034640
+13.360018	0.055063	-0.059851	9.844305	0.047697	0.089931	-0.034773
+13.361059	-0.023940	-0.019152	9.885003	0.047164	0.088066	-0.036239
+13.362061	-0.062245	0.007182	9.798818	0.048230	0.085934	-0.036372
+13.363056	-0.004788	-0.071821	9.820364	0.051294	0.088066	-0.035040
+13.364058	-0.004788	-0.047881	9.815576	0.047963	0.091530	-0.032642
+13.365058	-0.007182	-0.026334	9.894580	0.046364	0.090464	-0.032242
+13.366027	0.002394	-0.062245	9.877821	0.046631	0.088466	-0.036106
+13.367057	0.016758	0.009576	9.817970	0.047164	0.087666	-0.036905
+13.368038	0.031123	0.043093	9.863457	0.046897	0.088066	-0.033175
+13.369046	0.016758	-0.028729	9.789242	0.047963	0.089798	-0.035173
+13.370025	-0.038305	-0.033517	9.832334	0.048363	0.086734	-0.040236
+13.371016	-0.004788	0.016758	9.875427	0.048230	0.086201	-0.039836
+13.372058	0.047881	-0.016758	9.829940	0.044499	0.087400	-0.036106
+13.373060	0.079003	0.028729	9.815576	0.043700	0.088998	-0.037172
+13.374059	0.047881	0.026334	9.885003	0.043966	0.087000	-0.038237
+13.375057	0.019152	0.011970	9.889792	0.045832	0.087266	-0.035573
+13.376058	0.026334	0.038305	9.806000	0.048096	0.090331	-0.033574
+13.377061	0.023940	-0.038305	9.851487	0.047164	0.090597	-0.031443
+13.378062	0.009576	-0.014364	9.849093	0.047430	0.090997	-0.033441
+13.379059	-0.019152	-0.031123	9.813182	0.047963	0.089798	-0.038237
+13.380038	-0.021546	-0.019152	9.791636	0.047297	0.088332	-0.038504
+13.381016	-0.014364	-0.014364	9.841911	0.047564	0.088332	-0.038637
+13.382057	0.014364	-0.019152	9.837123	0.047430	0.090331	-0.036772
+13.383044	-0.033517	0.031123	9.810788	0.045698	0.090064	-0.037172
+13.383988	-0.035911	0.011970	9.791636	0.046764	0.088732	-0.035839
+13.384970	0.031123	0.021546	9.803606	0.046631	0.086334	-0.033041
+13.386056	-0.011970	0.033517	9.873033	0.045032	0.085401	-0.038904
+13.387057	-0.031123	-0.047881	9.825152	0.046764	0.088865	-0.038104
+13.388057	0.035911	0.004788	9.748543	0.045965	0.089798	-0.037038
+13.389057	0.019152	0.043093	9.822758	0.044899	0.089798	-0.036639
+13.390051	0.057457	0.002394	9.820364	0.046897	0.088199	-0.034374
+13.391028	0.002394	-0.064639	9.796424	0.045698	0.087799	-0.032508
+13.392024	0.059851	0.028729	9.801212	0.044899	0.087666	-0.033841
+13.393025	0.033517	-0.019152	9.755725	0.045965	0.088998	-0.037971
+13.394027	0.011970	-0.071821	9.817970	0.047031	0.088199	-0.039170
+13.395037	-0.059851	-0.011970	9.825152	0.049296	0.086334	-0.036639
+13.396122	-0.002394	-0.033517	9.829940	0.049029	0.087666	-0.035573
+13.397033	-0.011970	-0.062245	9.748543	0.046631	0.089398	-0.033974
+13.398038	0.019152	-0.031123	9.750937	0.044499	0.089531	-0.035440
+13.399027	0.026334	-0.016758	9.861063	0.044766	0.087266	-0.036239
+13.400024	-0.040699	-0.059851	9.806000	0.046631	0.085934	-0.035972
+13.401006	0.019152	0.021546	9.719814	0.048096	0.085801	-0.035839
+13.401944	0.023940	0.011970	9.817970	0.046231	0.087400	-0.036505
+13.402953	0.028729	0.004788	9.810788	0.045432	0.085668	-0.035573
+13.403968	-0.011970	0.023940	9.834729	0.045698	0.086467	-0.036639
+13.404971	-0.009576	0.004788	9.887397	0.046364	0.090997	-0.037971
+13.406007	-0.016758	-0.023940	9.729391	0.046764	0.091663	-0.033841
+13.407022	-0.043093	-0.019152	9.803606	0.048496	0.088199	-0.033574
+13.408041	-0.021546	-0.033517	9.794030	0.047031	0.087666	-0.037305
+13.408994	0.035911	-0.021546	9.794030	0.044899	0.085801	-0.036106
+13.410016	0.011970	-0.021546	9.798818	0.046631	0.085534	-0.037172
+13.411020	0.035911	-0.007182	9.796424	0.047430	0.087933	-0.036505
+13.412022	0.050275	0.043093	9.806000	0.047430	0.087400	-0.034374
+13.413041	0.033517	0.014364	9.841911	0.047963	0.088998	-0.036106
+13.414045	0.021546	0.035911	9.832334	0.045032	0.085801	-0.035306
+13.415043	0.009576	0.014364	9.784454	0.044632	0.083936	-0.037838
+13.416047	0.002394	-0.007182	9.798818	0.048096	0.083536	-0.037038
+13.417020	-0.007182	-0.007182	9.736573	0.051560	0.085268	-0.032109
+13.418026	-0.004788	-0.014364	9.782060	0.050361	0.087000	-0.036372
+13.419021	0.047881	-0.007182	9.896974	0.045832	0.086867	-0.037571
+13.420044	0.107732	-0.026334	9.908944	0.045832	0.087000	-0.035306
+13.421007	0.043093	-0.047881	9.844305	0.045565	0.088466	-0.033974
+13.422044	0.014364	0.035911	9.863457	0.047430	0.088732	-0.033841
+13.423042	0.023940	0.028729	9.861063	0.049828	0.089665	-0.034773
+13.424042	0.026334	0.019152	9.798818	0.049029	0.091530	-0.035706
+13.425043	0.009576	0.000000	9.817970	0.046764	0.089798	-0.036639
+13.426044	-0.026334	0.050275	9.889792	0.046764	0.085534	-0.036905
+13.427037	0.040699	0.038305	9.885003	0.046231	0.086067	-0.035972
+13.428042	0.033517	-0.038305	9.798818	0.048230	0.087933	-0.035706
+13.429023	-0.026334	-0.002394	9.837123	0.049429	0.090064	-0.036372
+13.430012	-0.040699	-0.002394	9.813182	0.048230	0.089931	-0.039303
+13.431020	-0.002394	0.009576	9.801212	0.048363	0.085534	-0.037571
+13.432021	0.045487	-0.014364	9.803606	0.049695	0.085668	-0.037571
+13.433021	0.009576	-0.004788	9.712632	0.049695	0.086867	-0.039703
+13.434042	0.071821	-0.045487	9.703056	0.049296	0.085002	-0.038637
+13.435030	0.043093	-0.033517	9.810788	0.048096	0.084469	-0.036239
+13.436043	0.021546	0.009576	9.806000	0.046897	0.086201	-0.033441
+13.437042	0.045487	-0.023940	9.760513	0.045698	0.085534	-0.035839
+13.438044	0.014364	0.002394	9.777271	0.043966	0.086467	-0.037971
+13.439043	0.021546	0.023940	9.837123	0.046231	0.088066	-0.036772
+13.440042	0.016758	-0.011970	9.894580	0.048629	0.088732	-0.036106
+13.441044	0.007182	0.007182	9.858669	0.048363	0.088732	-0.033974
+13.442034	-0.004788	0.019152	9.806000	0.047697	0.087799	-0.030377
+13.443032	-0.093368	-0.031123	9.738967	0.047297	0.087266	-0.031043
+13.444027	-0.047881	-0.050275	9.703056	0.047297	0.087933	-0.037704
+13.445022	0.002394	-0.035911	9.743755	0.046364	0.087933	-0.037305
+13.446033	-0.011970	0.002394	9.683904	0.046231	0.088066	-0.033841
+13.447017	0.002394	-0.047881	9.765301	0.047963	0.088865	-0.034240
+13.448028	0.033517	-0.052669	9.808394	0.048096	0.088732	-0.033041
+13.449028	0.033517	0.007182	9.827546	0.050228	0.088865	-0.033041
+13.450018	-0.016758	-0.011970	9.798818	0.048096	0.087400	-0.035440
+13.451010	-0.004788	-0.002394	9.803606	0.048096	0.088332	-0.036772
+13.452032	0.019152	0.014364	9.803606	0.047564	0.089665	-0.033574
+13.453032	-0.031123	0.019152	9.743755	0.047564	0.087799	-0.036639
+13.453980	-0.050275	-0.047881	9.762907	0.047031	0.086467	-0.041035
+13.454972	-0.038305	-0.028729	9.779666	0.046098	0.086067	-0.036905
+13.455969	-0.016758	0.016758	9.844305	0.046631	0.086334	-0.035040
+13.456981	-0.028729	0.059851	9.827546	0.047430	0.087266	-0.037438
+13.457973	0.019152	-0.011970	9.767695	0.045965	0.087666	-0.037971
+13.458973	-0.007182	-0.016758	9.777271	0.046764	0.087933	-0.037438
+13.459969	-0.004788	-0.093368	9.806000	0.048363	0.087666	-0.035040
+13.460973	-0.014364	-0.098156	9.868245	0.048629	0.089665	-0.036772
+13.461976	0.023940	-0.090974	9.719814	0.050095	0.090997	-0.038904
+13.462977	0.002394	-0.016758	9.736573	0.049828	0.089665	-0.038371
+13.463977	-0.021546	-0.007182	9.846699	0.047830	0.087799	-0.037438
+13.464978	0.019152	0.016758	9.731785	0.046764	0.086201	-0.037571
+13.465984	0.028729	0.016758	9.707844	0.048496	0.085668	-0.034773
+13.466987	0.009576	-0.035911	9.724603	0.048896	0.087000	-0.036106
+13.467966	-0.028729	-0.033517	9.798818	0.045565	0.088332	-0.038504
+13.468987	-0.038305	0.011970	9.853881	0.043567	0.088199	-0.034907
+13.469970	-0.038305	0.028729	9.762907	0.043833	0.087400	-0.037571
+13.470987	0.004788	0.007182	9.798818	0.045165	0.086467	-0.035839
+13.471989	0.014364	-0.038305	9.822758	0.046364	0.088466	-0.034374
+13.472983	0.031123	-0.021546	9.808394	0.046231	0.087400	-0.035040
+13.473982	0.033517	0.002394	9.779666	0.046631	0.084335	-0.037172
+13.474986	0.019152	-0.055063	9.808394	0.047564	0.085401	-0.038504
+13.475987	0.033517	0.009576	9.846699	0.047430	0.088599	-0.035306
+13.476982	0.009576	0.035911	9.868245	0.048096	0.090331	-0.033974
+13.477992	0.043093	0.071821	9.825152	0.048230	0.088066	-0.034240
+13.478990	0.026334	-0.002394	9.858669	0.046231	0.085801	-0.037838
+13.479991	0.009576	0.002394	9.810788	0.044499	0.084602	-0.039170
+13.480992	-0.016758	-0.014364	9.837123	0.047297	0.086067	-0.035173
+13.481991	-0.019152	-0.007182	9.784454	0.046764	0.085268	-0.034640
+13.482986	-0.045487	-0.004788	9.827546	0.049029	0.085801	-0.035040
+13.483991	-0.040699	-0.052669	9.868245	0.048629	0.086467	-0.038237
+13.484991	0.023940	-0.057457	9.822758	0.046231	0.086201	-0.039703
+13.485992	-0.014364	0.011970	9.750937	0.045565	0.087133	-0.036905
+13.486991	-0.026334	0.059851	9.863457	0.049296	0.087666	-0.035040
+13.487991	-0.026334	0.059851	9.863457	0.047963	0.088066	-0.037172
+13.488992	0.045487	-0.004788	9.806000	0.047297	0.089265	-0.036372
+13.489994	0.004788	0.023940	9.717420	0.045165	0.090198	-0.035972
+13.490990	-0.011970	0.043093	9.712632	0.044100	0.089132	-0.036505
+13.491991	0.028729	0.014364	9.806000	0.045432	0.086067	-0.035839
+13.492991	0.040699	-0.040699	9.782060	0.045565	0.083270	-0.034640
+13.493991	0.035911	0.016758	9.741361	0.047430	0.086067	-0.037438
+13.494990	-0.014364	-0.047881	9.753331	0.047430	0.090331	-0.038237
+13.495986	0.038305	-0.074215	9.726997	0.046631	0.091263	-0.037838
+13.496991	0.033517	0.002394	9.705450	0.046098	0.089531	-0.035839
+13.497992	0.009576	-0.007182	9.753331	0.048096	0.089931	-0.034773
+13.498986	0.004788	-0.016758	9.786848	0.046897	0.090464	-0.033441
+13.499991	0.035911	0.002394	9.856275	0.045565	0.088332	-0.035706
+13.500973	0.050275	-0.031123	9.832334	0.046364	0.088066	-0.039170
+13.501977	0.031123	-0.045487	9.841911	0.047963	0.086600	-0.037704
+13.502967	-0.047881	-0.059851	9.815576	0.047830	0.087400	-0.036772
+13.504053	0.043093	-0.038305	9.770089	0.047031	0.086867	-0.037438
+13.505057	0.002394	-0.011970	9.772483	0.047297	0.088732	-0.035972
+13.506024	-0.011970	-0.011970	9.808394	0.049562	0.088599	-0.038371
+13.507048	0.002394	0.016758	9.815576	0.046897	0.086067	-0.039037
+13.508057	0.023940	0.004788	9.760513	0.045432	0.085801	-0.036505
+13.509056	0.040699	0.002394	9.765301	0.047564	0.087400	-0.037438
+13.510064	-0.019152	0.035911	9.798818	0.048230	0.087666	-0.039037
+13.511054	-0.004788	-0.026334	9.875427	0.049429	0.085401	-0.033308
+13.512043	0.021546	-0.069427	9.810788	0.048763	0.087000	-0.033974
+13.513057	0.057457	-0.031123	9.832334	0.047297	0.088865	-0.037971
+13.514058	-0.002394	-0.045487	9.837123	0.045032	0.089398	-0.038637
+13.515019	-0.007182	0.009576	9.806000	0.043433	0.089132	-0.036106
+13.516051	0.007182	-0.019152	9.772483	0.044499	0.088066	-0.034240
+13.517054	0.019152	-0.026334	9.765301	0.045698	0.090331	-0.037438
+13.517985	-0.028729	-0.052669	9.810788	0.045832	0.089398	-0.039436
+13.519054	-0.007182	-0.031123	9.849093	0.048629	0.088466	-0.039170
+13.519975	0.000000	-0.028729	9.906550	0.046098	0.087133	-0.037704
+13.521050	-0.023940	0.004788	9.858669	0.045432	0.086334	-0.033441
+13.522022	-0.011970	-0.011970	9.786848	0.046498	0.089931	-0.035573
+13.523051	-0.023940	-0.009576	9.832334	0.046231	0.088199	-0.033041
+13.524056	-0.026334	-0.007182	9.796424	0.043567	0.086867	-0.033708
+13.525056	-0.004788	0.000000	9.822758	0.043700	0.088998	-0.032908
+13.526058	0.009576	0.002394	9.837123	0.046231	0.089265	-0.034907
+13.527054	0.059851	0.016758	9.817970	0.047830	0.088732	-0.037571
+13.528054	0.033517	0.004788	9.801212	0.046764	0.091263	-0.036372
+13.529002	-0.011970	0.031123	9.760513	0.046231	0.088998	-0.033441
+13.530058	0.059851	-0.033517	9.868245	0.047031	0.089798	-0.037305
+13.531028	0.047881	-0.074215	9.863457	0.048763	0.089132	-0.039969
+13.531997	-0.007182	-0.040699	9.806000	0.048363	0.086867	-0.040502
+13.533051	0.019152	0.009576	9.889792	0.045698	0.086201	-0.036905
+13.534035	0.014364	-0.033517	9.853881	0.044899	0.088466	-0.035306
+13.535022	0.023940	-0.002394	9.741361	0.046364	0.088732	-0.037704
+13.536036	-0.031123	-0.007182	9.798818	0.045565	0.088066	-0.037704
+13.537029	-0.055063	0.000000	9.782060	0.043300	0.089531	-0.035040
+13.538015	-0.035911	-0.021546	9.829940	0.043966	0.089132	-0.031975
+13.539092	-0.007182	0.035911	9.829940	0.047963	0.088466	-0.035706
+13.540092	-0.019152	0.021546	9.806000	0.047430	0.087266	-0.035706
+13.541049	0.009576	-0.009576	9.791636	0.048496	0.086600	-0.037038
+13.542078	0.028729	0.009576	9.791636	0.048896	0.086734	-0.037971
+13.543090	-0.011970	0.021546	9.815576	0.046631	0.088066	-0.038104
+13.544093	-0.031123	-0.007182	9.815576	0.045432	0.084868	-0.040769
+13.545037	0.031123	-0.016758	9.789242	0.045299	0.085268	-0.037438
+13.546043	-0.011970	-0.011970	9.717420	0.046364	0.086600	-0.036905
+13.547091	-0.011970	-0.038305	9.715026	0.047830	0.086201	-0.036905
+13.548003	-0.026334	0.009576	9.794030	0.045299	0.087133	-0.036372
+13.549091	-0.007182	-0.033517	9.829940	0.045965	0.087400	-0.038770
+13.550004	-0.019152	-0.026334	9.779666	0.046364	0.087933	-0.036239
+13.551050	0.004788	-0.055063	9.736573	0.046231	0.088066	-0.036372
+13.552072	0.016758	-0.033517	9.772483	0.046897	0.092196	-0.037172
+13.553093	0.021546	0.002394	9.755725	0.047697	0.089531	-0.038504
+13.554019	-0.045487	-0.007182	9.794030	0.049429	0.087133	-0.035040
+13.555093	0.014364	0.000000	9.765301	0.050095	0.088599	-0.034507
+13.556093	0.047881	0.023940	9.796424	0.050228	0.090064	-0.034107
+13.557091	0.033517	0.031123	9.774877	0.047564	0.088199	-0.034240
+13.558092	-0.028729	-0.040699	9.815576	0.044499	0.088066	-0.033441
+13.559094	0.019152	-0.016758	9.832334	0.047164	0.088066	-0.034240
+13.560030	0.047881	0.014364	9.760513	0.049029	0.088865	-0.035972
+13.561089	-0.016758	-0.002394	9.798818	0.048629	0.089531	-0.038504
+13.562096	0.007182	0.007182	9.930490	0.045432	0.089665	-0.037305
+13.563091	0.043093	0.016758	9.858669	0.043833	0.087533	-0.038237
+13.564092	0.000000	-0.038305	9.841911	0.046631	0.088332	-0.037038
+13.565037	-0.019152	-0.009576	9.906550	0.047297	0.090198	-0.035440
+13.566034	0.009576	-0.004788	9.734179	0.047564	0.087000	-0.038770
+13.567090	0.031123	0.007182	9.753331	0.047697	0.084602	-0.035440
+13.568091	0.019152	0.019152	9.765301	0.047430	0.087000	-0.032908
+13.569032	0.000000	-0.023940	9.865851	0.047164	0.087266	-0.032508
+13.570092	-0.028729	-0.004788	9.911338	0.046764	0.086600	-0.034773
+13.571091	0.009576	0.004788	9.887397	0.047963	0.086600	-0.035839
+13.572091	0.014364	-0.062245	9.815576	0.047430	0.087133	-0.037571
+13.573017	0.023940	-0.023940	9.755725	0.046231	0.086600	-0.037305
+13.573992	0.009576	0.023940	9.801212	0.045698	0.087799	-0.037704
+13.574991	-0.026334	0.002394	9.767695	0.044899	0.088732	-0.035573
+13.576091	0.023940	-0.047881	9.758119	0.045432	0.087133	-0.035040
+13.577093	0.033517	-0.038305	9.762907	0.046897	0.086600	-0.037838
+13.578092	-0.026334	-0.026334	9.779666	0.049429	0.085668	-0.038237
+13.579036	0.009576	-0.026334	9.815576	0.047430	0.083802	-0.033175
+13.580004	-0.004788	-0.004788	9.839517	0.047031	0.086067	-0.035706
+13.581093	-0.019152	0.021546	9.858669	0.048230	0.089265	-0.040902
+13.582041	-0.011970	0.031123	9.817970	0.048363	0.088332	-0.038504
+13.583092	-0.007182	0.071821	9.817970	0.046764	0.087133	-0.035839
+13.584087	0.028729	0.069427	9.875427	0.046098	0.088865	-0.035173
+13.585025	0.052669	0.023940	9.777271	0.047564	0.088998	-0.036905
+13.586094	0.093368	-0.019152	9.808394	0.049029	0.088066	-0.035040
+13.587091	0.019152	0.014364	9.801212	0.047297	0.085934	-0.035839
+13.588069	0.023940	-0.009576	9.849093	0.046897	0.090331	-0.035040
+13.589090	0.062245	-0.028729	9.837123	0.045698	0.092596	-0.033574
+13.590045	0.038305	0.026334	9.820364	0.045432	0.088599	-0.033441
+13.591092	0.004788	0.088580	9.770089	0.045698	0.087133	-0.039170
+13.592094	0.004788	-0.016758	9.798818	0.046498	0.086734	-0.040369
+13.593092	0.033517	-0.016758	9.829940	0.046498	0.085934	-0.038770
+13.594094	0.016758	-0.004788	9.822758	0.047963	0.087666	-0.036905
+13.595090	0.026334	-0.035911	9.908944	0.046098	0.090597	-0.038504
+13.596061	0.004788	0.009576	9.899368	0.045565	0.089265	-0.035839
+13.597024	-0.026334	-0.040699	9.789242	0.046897	0.087666	-0.033708
+13.597997	-0.052669	0.000000	9.849093	0.046498	0.085268	-0.032109
+13.599090	-0.019152	0.021546	9.825152	0.047963	0.087400	-0.034107
+13.599989	0.009576	0.009576	9.731785	0.049562	0.087799	-0.033308
+13.601091	0.007182	-0.038305	9.786848	0.047697	0.086600	-0.036772
+13.602003	0.016758	0.002394	9.839517	0.045432	0.086334	-0.034907
+13.603090	-0.004788	-0.016758	9.827546	0.047164	0.087933	-0.035706
+13.604091	-0.069427	0.000000	9.839517	0.048496	0.089265	-0.036905
+13.605089	-0.009576	0.007182	9.810788	0.047830	0.088599	-0.034240
+13.606092	0.062245	0.002394	9.817970	0.046897	0.089265	-0.036372
+13.607022	0.071821	-0.047881	9.825152	0.046231	0.088998	-0.038104
+13.608090	0.011970	-0.026334	9.753331	0.046364	0.083669	-0.038904
+13.609092	-0.007182	-0.002394	9.782060	0.043700	0.084069	-0.036639
+13.610093	0.019152	-0.011970	9.822758	0.045698	0.088865	-0.038371
+13.611091	-0.014364	-0.035911	9.837123	0.047830	0.086334	-0.040236
+13.612091	-0.047881	-0.076609	9.846699	0.048363	0.085934	-0.035440
+13.613090	0.026334	-0.052669	9.834729	0.045299	0.087933	-0.031842
+13.614093	0.050275	0.026334	9.839517	0.046364	0.087933	-0.033574
+13.615046	0.047881	-0.004788	9.820364	0.047297	0.088466	-0.038237
+13.616011	0.016758	-0.002394	9.753331	0.047697	0.087799	-0.037838
+13.617075	-0.014364	0.035911	9.695874	0.047430	0.087533	-0.036905
+13.618002	0.016758	0.028729	9.724603	0.047297	0.088332	-0.038770
+13.619091	0.000000	-0.011970	9.806000	0.047164	0.088332	-0.039570
+13.620048	-0.011970	-0.033517	9.765301	0.048096	0.086067	-0.037704
+13.621087	0.028729	0.002394	9.765301	0.046764	0.085934	-0.034240
+13.622092	0.009576	-0.009576	9.825152	0.045432	0.088466	-0.037038
+13.623091	0.011970	0.011970	9.707844	0.045565	0.090597	-0.037571
+13.624091	-0.007182	0.023940	9.743755	0.047564	0.089398	-0.034907
+13.625023	-0.014364	0.014364	9.717420	0.048896	0.089531	-0.035573
+13.626093	-0.028729	0.014364	9.734179	0.047697	0.087666	-0.035573
+13.627036	-0.038305	-0.028729	9.734179	0.045832	0.085934	-0.037305
+13.628091	0.026334	0.004788	9.786848	0.047564	0.085135	-0.035573
+13.629091	-0.004788	-0.007182	9.853881	0.049429	0.087133	-0.037038
+13.630021	0.050275	-0.033517	9.762907	0.049562	0.090464	-0.036905
+13.631091	-0.014364	-0.004788	9.738967	0.048363	0.088998	-0.035040
+13.632090	-0.014364	0.074215	9.786848	0.045832	0.087000	-0.031842
+13.633092	0.023940	0.047881	9.779666	0.045165	0.090064	-0.035306
+13.634021	0.031123	-0.014364	9.863457	0.045299	0.088998	-0.039436
+13.635009	0.004788	0.028729	9.844305	0.046231	0.087666	-0.037704
+13.636090	0.033517	-0.002394	9.786848	0.048896	0.088199	-0.039170
+13.637035	-0.011970	-0.016758	9.765301	0.048763	0.089531	-0.037704
+13.638092	0.002394	0.000000	9.722208	0.046498	0.088332	-0.036905
+13.639092	-0.019152	0.045487	9.827546	0.047430	0.087933	-0.035706
+13.640091	-0.016758	0.021546	9.817970	0.046764	0.088732	-0.035573
+13.641090	-0.043093	-0.014364	9.810788	0.047430	0.086201	-0.039170
+13.642091	-0.040699	0.007182	9.815576	0.045832	0.085002	-0.036239
+13.643049	0.007182	-0.002394	9.865851	0.044100	0.087000	-0.034907
+13.644060	-0.004788	-0.004788	9.815576	0.045698	0.087266	-0.036639
+13.645091	0.055063	0.016758	9.882609	0.046231	0.086467	-0.038237
+13.646036	0.047881	-0.009576	9.760513	0.044366	0.084602	-0.037838
+13.647090	0.014364	0.000000	9.705450	0.047963	0.085534	-0.037704
+13.647999	0.028729	0.000000	9.695874	0.049029	0.087000	-0.036905
+13.649092	0.059851	-0.014364	9.791636	0.046231	0.086867	-0.035972
+13.650016	0.028729	0.043093	9.877821	0.046498	0.087933	-0.038237
+13.651038	0.043093	0.028729	9.837123	0.047697	0.088199	-0.038504
+13.652054	0.004788	-0.074215	9.820364	0.047430	0.087266	-0.037038
+13.653034	-0.004788	-0.038305	9.803606	0.044899	0.087933	-0.036239
+13.654095	0.004788	0.033517	9.801212	0.047564	0.086201	-0.035440
+13.655088	0.009576	-0.026334	9.827546	0.047830	0.086734	-0.034907
+13.656033	0.050275	0.019152	9.794030	0.046764	0.089398	-0.036505
+13.657092	0.002394	-0.055063	9.827546	0.047830	0.090198	-0.035706
+13.658091	0.004788	0.002394	9.784454	0.048763	0.088865	-0.036905
+13.659018	0.050275	0.043093	9.719814	0.047297	0.088066	-0.037038
+13.660091	0.067033	-0.011970	9.755725	0.048363	0.086867	-0.038504
+13.661091	-0.004788	0.004788	9.810788	0.048896	0.084602	-0.038770
+13.662021	-0.038305	-0.038305	9.887397	0.046897	0.085002	-0.036772
+13.663015	0.016758	-0.002394	9.863457	0.044499	0.088066	-0.035306
+13.664091	0.047881	0.002394	9.844305	0.044899	0.090198	-0.035440
+13.665092	0.002394	-0.014364	9.817970	0.045965	0.087000	-0.035440
+13.665999	0.007182	-0.028729	9.863457	0.045432	0.085268	-0.037172
+13.667021	-0.004788	-0.059851	9.822758	0.046231	0.085668	-0.039836
+13.668090	0.033517	-0.016758	9.820364	0.046098	0.084202	-0.038104
+13.669091	0.043093	0.028729	9.817970	0.044366	0.085934	-0.033441
+13.670094	-0.019152	0.023940	9.801212	0.043966	0.088066	-0.035573
+13.671090	0.000000	0.038305	9.758119	0.047430	0.088732	-0.037172
+13.672048	-0.026334	0.028729	9.796424	0.047564	0.087799	-0.034507
+13.673075	0.011970	0.004788	9.813182	0.046098	0.087666	-0.037971
+13.674094	0.038305	0.052669	9.741361	0.045832	0.087400	-0.039303
+13.675089	0.016758	-0.021546	9.853881	0.045565	0.084335	-0.038104
+13.676090	0.000000	-0.028729	9.908944	0.045965	0.084868	-0.035306
+13.677089	-0.081397	0.002394	9.849093	0.047430	0.086334	-0.033708
+13.678091	-0.040699	0.011970	9.837123	0.046498	0.087266	-0.033041
+13.679091	-0.016758	0.021546	9.794030	0.046764	0.085401	-0.035040
+13.680029	0.035911	0.038305	9.731785	0.047564	0.083802	-0.037971
+13.681017	0.035911	0.023940	9.837123	0.044100	0.083802	-0.037438
+13.682013	0.014364	-0.045487	9.791636	0.041835	0.086600	-0.034240
+13.683091	-0.023940	-0.088580	9.705450	0.043567	0.088865	-0.034907
+13.684089	-0.038305	0.021546	9.791636	0.045565	0.090331	-0.036505
+13.685034	-0.038305	0.014364	9.803606	0.045032	0.089531	-0.036372
+13.686091	-0.011970	0.045487	9.729391	0.044499	0.088998	-0.034907
+13.687088	0.002394	0.019152	9.846699	0.043433	0.086067	-0.035839
+13.688090	-0.023940	0.009576	9.856275	0.044766	0.085534	-0.035306
+13.689091	-0.026334	0.016758	9.803606	0.045299	0.085401	-0.036106
+13.690037	-0.019152	-0.023940	9.758119	0.046231	0.086201	-0.036239
+13.691045	-0.026334	-0.023940	9.746149	0.046498	0.089931	-0.035972
+13.692055	0.016758	-0.031123	9.801212	0.046764	0.088998	-0.037038
+13.693090	0.026334	-0.052669	9.782060	0.045565	0.087933	-0.037172
+13.694091	-0.016758	-0.045487	9.777271	0.045565	0.086867	-0.039703
+13.695091	-0.016758	0.000000	9.813182	0.046764	0.087666	-0.035306
+13.696091	-0.021546	0.028729	9.784454	0.047830	0.087533	-0.033974
+13.697094	-0.009576	-0.009576	9.794030	0.045299	0.086867	-0.036372
+13.698033	0.043093	-0.004788	9.789242	0.046897	0.089265	-0.039703
+13.699035	-0.021546	0.023940	9.868245	0.049162	0.088066	-0.037305
+13.700022	0.045487	-0.014364	9.834729	0.048629	0.088998	-0.035706
+13.701047	0.033517	-0.033517	9.846699	0.047697	0.088998	-0.033308
+13.701997	0.055063	0.040699	9.820364	0.047564	0.088865	-0.035173
+13.703087	0.059851	-0.026334	9.755725	0.049695	0.088332	-0.036505
+13.704091	0.045487	-0.007182	9.803606	0.049162	0.088466	-0.036639
+13.705090	0.009576	-0.052669	9.817970	0.047031	0.088199	-0.037172
+13.706093	-0.023940	-0.019152	9.791636	0.045698	0.089398	-0.036505
+13.707090	0.043093	0.011970	9.791636	0.044499	0.088466	-0.037438
+13.708088	-0.014364	0.055063	9.841911	0.043700	0.088466	-0.038637
+13.709091	-0.033517	0.026334	9.834729	0.047430	0.087933	-0.038237
+13.710017	0.011970	0.019152	9.817970	0.048230	0.087533	-0.037971
+13.711018	0.004788	-0.023940	9.849093	0.046897	0.087400	-0.038504
+13.712088	0.028729	0.002394	9.829940	0.046897	0.085801	-0.039570
+13.713091	0.004788	-0.004788	9.822758	0.045165	0.086067	-0.035173
+13.714063	0.016758	0.007182	9.820364	0.047430	0.086467	-0.037704
+13.715115	0.002394	0.007182	9.825152	0.048230	0.083536	-0.038637
+13.716113	0.069427	-0.014364	9.806000	0.045698	0.086867	-0.037571
+13.717115	0.071821	-0.016758	9.722208	0.045698	0.087266	-0.038104
+13.718047	-0.019152	0.007182	9.753331	0.046498	0.088066	-0.034507
+13.719073	0.028729	0.007182	9.789242	0.046631	0.088732	-0.035972
+13.720117	0.069427	-0.021546	9.786848	0.049429	0.088732	-0.038104
+13.721051	0.062245	-0.004788	9.856275	0.048629	0.087533	-0.038237
+13.722101	0.016758	-0.009576	9.870639	0.047297	0.087266	-0.036639
+13.723115	-0.004788	-0.045487	9.817970	0.046364	0.087533	-0.034507
+13.724114	0.043093	-0.033517	9.827546	0.046498	0.089132	-0.031576
+13.725110	0.045487	-0.055063	9.844305	0.047031	0.088466	-0.033708
+13.726044	0.043093	-0.028729	9.880215	0.046364	0.085401	-0.037704
+13.727110	0.045487	-0.011970	9.892186	0.045032	0.084335	-0.036239
+13.728111	0.040699	-0.016758	9.841911	0.046098	0.085002	-0.035972
+13.729068	0.021546	0.035911	9.786848	0.047164	0.085401	-0.034374
+13.730058	-0.081397	-0.002394	9.827546	0.048629	0.086734	-0.035839
+13.731045	-0.026334	0.023940	9.784454	0.047697	0.085534	-0.034240
+13.732110	-0.035911	-0.026334	9.786848	0.046764	0.088066	-0.037172
+13.733110	-0.004788	-0.023940	9.813182	0.045032	0.085534	-0.033574
+13.734117	-0.002394	0.002394	9.782060	0.046764	0.084335	-0.035173
+13.735057	0.028729	0.033517	9.736573	0.047564	0.086201	-0.035706
+13.736110	0.038305	0.035911	9.825152	0.049962	0.089798	-0.031443
+13.737114	0.019152	-0.002394	9.762907	0.051028	0.090064	-0.031043
+13.738054	-0.031123	0.011970	9.865851	0.049029	0.089931	-0.033574
+13.739085	-0.026334	0.057457	9.851487	0.048363	0.090064	-0.039037
+13.740112	0.043093	-0.004788	9.813182	0.048896	0.091130	-0.043167
+13.741048	0.031123	-0.040699	9.772483	0.048096	0.089798	-0.039170
+13.742044	0.040699	-0.009576	9.815576	0.047963	0.088466	-0.037571
+13.743110	0.026334	-0.016758	9.868245	0.046631	0.087666	-0.038770
+13.744112	-0.009576	-0.002394	9.796424	0.046231	0.088599	-0.039037
+13.745114	0.009576	0.057457	9.841911	0.046764	0.089265	-0.038904
+13.746116	0.000000	0.028729	9.896974	0.047031	0.088599	-0.037438
+13.747067	0.021546	-0.004788	9.832334	0.047830	0.088998	-0.034240
+13.748050	0.011970	-0.014364	9.801212	0.046231	0.089665	-0.034640
+13.749020	-0.007182	-0.002394	9.806000	0.045165	0.085002	-0.039570
+13.750044	0.031123	0.050275	9.791636	0.046098	0.085934	-0.041035
+13.751112	0.002394	0.007182	9.817970	0.046897	0.086201	-0.037438
+13.752053	-0.023940	-0.055063	9.868245	0.048629	0.087933	-0.037571
+13.753077	0.043093	-0.083792	9.798818	0.047697	0.088732	-0.038237
+13.754116	0.050275	-0.016758	9.863457	0.047830	0.089132	-0.036239
+13.755112	0.019152	0.035911	9.858669	0.049296	0.087133	-0.033708
+13.756086	0.023940	0.016758	9.810788	0.049962	0.086067	-0.036372
+13.757066	0.050275	0.040699	9.815576	0.047430	0.087133	-0.039037
+13.758111	0.023940	-0.014364	9.719814	0.044899	0.087933	-0.042101
+13.759048	0.023940	-0.007182	9.762907	0.045032	0.085534	-0.042234
+13.760067	0.050275	0.021546	9.815576	0.045965	0.086334	-0.037305
+13.761026	0.011970	-0.016758	9.738967	0.050628	0.088865	-0.038637
+13.762116	0.033517	-0.031123	9.743755	0.051028	0.089531	-0.040103
+13.763112	-0.045487	-0.009576	9.738967	0.048230	0.087266	-0.036772
+13.764113	-0.014364	0.074215	9.798818	0.045832	0.088066	-0.033574
+13.765053	0.019152	0.004788	9.813182	0.045432	0.089665	-0.034374
+13.766068	0.000000	-0.062245	9.817970	0.045165	0.089665	-0.036505
+13.767107	-0.031123	-0.028729	9.779666	0.046231	0.091130	-0.034240
+13.768110	-0.021546	-0.021546	9.777271	0.045832	0.090597	-0.034773
+13.769111	0.011970	-0.047881	9.841911	0.046098	0.087266	-0.037305
+13.770087	0.002394	-0.019152	9.825152	0.047697	0.086334	-0.036239
+13.771112	0.007182	0.038305	9.806000	0.049695	0.088599	-0.034907
+13.772110	0.059851	-0.033517	9.760513	0.046897	0.088732	-0.034773
+13.773110	0.002394	-0.069427	9.750937	0.044899	0.085534	-0.035706
+13.774066	-0.002394	-0.074215	9.820364	0.045032	0.083802	-0.036639
+13.775073	-0.038305	0.028729	9.801212	0.045965	0.083669	-0.036239
+13.776110	-0.040699	0.059851	9.806000	0.048230	0.087000	-0.037305
+13.777114	0.033517	-0.004788	9.827546	0.047031	0.088066	-0.036905
+13.778115	0.047881	-0.019152	9.789242	0.048230	0.087933	-0.037838
+13.779114	0.000000	-0.045487	9.755725	0.046764	0.087400	-0.037838
+13.780058	0.000000	-0.004788	9.784454	0.045032	0.089531	-0.032508
+13.781090	-0.055063	0.047881	9.762907	0.043300	0.088998	-0.034240
+13.782114	-0.011970	-0.009576	9.750937	0.044899	0.085934	-0.035173
+13.783069	-0.023940	-0.026334	9.837123	0.045698	0.085268	-0.035573
+13.784107	-0.009576	-0.016758	9.760513	0.045965	0.085135	-0.035306
+13.785053	0.007182	0.002394	9.820364	0.047031	0.087133	-0.036639
+13.786116	0.007182	0.026334	9.803606	0.047963	0.088732	-0.039836
+13.787113	0.007182	0.019152	9.789242	0.046897	0.088599	-0.039436
+13.788114	0.021546	0.035911	9.779666	0.044233	0.085002	-0.037438
+13.789109	0.035911	0.016758	9.832334	0.047164	0.088332	-0.040902
+13.790127	-0.002394	-0.004788	9.803606	0.046764	0.090331	-0.041035
+13.791114	0.023940	0.021546	9.863457	0.045965	0.088865	-0.036905
+13.792068	0.009576	-0.040699	9.820364	0.047430	0.086867	-0.035040
+13.793111	0.076609	-0.009576	9.829940	0.049695	0.088066	-0.035972
+13.794116	0.002394	0.009576	9.813182	0.049162	0.088199	-0.036372
+13.795113	0.028729	-0.023940	9.822758	0.048096	0.088332	-0.038104
+13.796080	0.076609	0.009576	9.784454	0.050095	0.088865	-0.038637
+13.797113	0.064639	0.023940	9.782060	0.048496	0.091397	-0.037305
+13.798116	0.033517	-0.011970	9.736573	0.046631	0.088998	-0.035573
+13.799029	0.079003	-0.028729	9.798818	0.046364	0.087266	-0.036372
+13.800042	0.031123	-0.033517	9.880215	0.048496	0.085801	-0.035972
+13.801067	0.019152	-0.083792	9.810788	0.046364	0.086467	-0.036372
+13.802053	-0.002394	0.004788	9.796424	0.045565	0.088599	-0.036639
+13.803113	-0.014364	0.011970	9.794030	0.046764	0.090730	-0.036905
+13.804111	0.026334	0.028729	9.786848	0.047297	0.090064	-0.035173
+13.805113	0.021546	-0.019152	9.803606	0.046631	0.088732	-0.035173
+13.806114	0.002394	-0.031123	9.748543	0.046764	0.086067	-0.032109
+13.807110	0.000000	-0.026334	9.767695	0.048096	0.084602	-0.034507
+13.808075	0.009576	0.009576	9.837123	0.049562	0.087400	-0.037838
+13.809036	0.031123	0.016758	9.873033	0.048896	0.088998	-0.037838
+13.810015	0.023940	0.011970	9.803606	0.049029	0.090997	-0.034773
+13.810995	0.038305	-0.093368	9.774877	0.048496	0.090730	-0.037704
+13.812024	0.014364	-0.069427	9.796424	0.048230	0.090064	-0.035306
+13.813019	-0.004788	-0.004788	9.803606	0.048363	0.089265	-0.035839
+13.814041	0.035911	0.026334	9.834729	0.047697	0.087133	-0.038504
+13.815112	0.019152	-0.011970	9.794030	0.044899	0.086067	-0.036639
+13.816051	0.004788	0.000000	9.741361	0.043833	0.086201	-0.036239
+13.817041	0.043093	-0.016758	9.784454	0.046631	0.087933	-0.036772
+13.818033	0.050275	-0.047881	9.801212	0.046498	0.088865	-0.035440
+13.819039	0.000000	-0.055063	9.750937	0.045832	0.087400	-0.035839
+13.820039	-0.019152	0.000000	9.786848	0.048363	0.087933	-0.035440
+13.821035	0.002394	0.000000	9.777271	0.048896	0.089665	-0.038770
+13.822027	-0.007182	-0.021546	9.784454	0.046231	0.088998	-0.041035
+13.823020	0.033517	-0.059851	9.777271	0.043300	0.085934	-0.040103
+13.824040	0.043093	-0.057457	9.808394	0.045032	0.085401	-0.036905
+13.825040	0.047881	-0.038305	9.837123	0.048496	0.086067	-0.037438
+13.825997	0.043093	0.026334	9.808394	0.050894	0.088599	-0.037038
+13.826989	0.009576	0.038305	9.791636	0.049029	0.089132	-0.037571
+13.828007	-0.009576	0.007182	9.815576	0.047430	0.088865	-0.036505
+13.829009	-0.014364	-0.023940	9.810788	0.045432	0.090597	-0.037172
+13.830029	-0.007182	-0.055063	9.717420	0.045432	0.089265	-0.039570
+13.831035	0.000000	0.028729	9.691086	0.046631	0.088199	-0.035440
+13.832058	-0.009576	-0.002394	9.724603	0.045565	0.088865	-0.038237
+13.833047	-0.028729	0.014364	9.810788	0.043833	0.087266	-0.037838
+13.834058	-0.007182	-0.009576	9.832334	0.044100	0.086334	-0.038371
+13.835038	0.067033	-0.045487	9.875427	0.045299	0.086201	-0.036905
+13.836089	0.047881	-0.033517	9.748543	0.048896	0.087400	-0.033974
+13.837091	0.050275	0.038305	9.834729	0.049162	0.088865	-0.031709
+13.838092	0.028729	0.016758	9.810788	0.049296	0.088332	-0.035573
+13.839052	0.016758	0.038305	9.741361	0.045432	0.085668	-0.036639
+13.840090	0.088580	-0.023940	9.760513	0.046764	0.088599	-0.033308
+13.841091	0.031123	0.002394	9.789242	0.045432	0.089132	-0.032508
+13.842048	0.007182	-0.002394	9.827546	0.044499	0.086467	-0.036372
+13.843042	0.009576	-0.014364	9.837123	0.044499	0.088865	-0.038371
+13.844088	-0.028729	-0.004788	9.858669	0.045965	0.089665	-0.038904
+13.845089	-0.023940	-0.040699	9.856275	0.048096	0.089132	-0.037571
+13.846093	0.038305	-0.057457	9.844305	0.048230	0.085934	-0.036239
+13.847038	0.062245	-0.047881	9.815576	0.047963	0.088732	-0.036639
+13.848052	-0.035911	-0.009576	9.726997	0.047830	0.090064	-0.034240
+13.849021	0.021546	-0.023940	9.760513	0.046897	0.088732	-0.034107
+13.849992	-0.019152	-0.045487	9.863457	0.047697	0.087400	-0.038237
+13.850990	0.000000	-0.033517	9.810788	0.047830	0.088332	-0.035040
+13.852020	-0.009576	-0.033517	9.827546	0.048629	0.090997	-0.037571
+13.853048	-0.026334	-0.021546	9.798818	0.046498	0.089798	-0.037438
+13.854090	-0.007182	0.007182	9.789242	0.044499	0.090331	-0.037305
+13.855044	0.045487	-0.016758	9.791636	0.046764	0.088998	-0.036639
+13.856090	0.004788	0.045487	9.789242	0.047830	0.088199	-0.034240
+13.857024	-0.007182	0.000000	9.827546	0.047963	0.086067	-0.034773
+13.858092	0.009576	-0.026334	9.806000	0.046631	0.086467	-0.035306
+13.859061	0.035911	0.014364	9.774877	0.049029	0.085801	-0.036106
+13.860089	0.016758	0.000000	9.810788	0.047963	0.087266	-0.038637
+13.861045	-0.002394	0.028729	9.817970	0.045965	0.087266	-0.037305
+13.862032	-0.016758	-0.021546	9.803606	0.044499	0.089798	-0.033708
+13.863090	0.000000	-0.028729	9.841911	0.046231	0.092063	-0.039969
+13.864089	0.000000	-0.031123	9.858669	0.045565	0.088466	-0.037571
+13.865091	0.021546	-0.007182	9.784454	0.045565	0.084602	-0.033308
+13.866094	0.038305	-0.028729	9.846699	0.048763	0.086067	-0.032508
+13.867089	0.028729	0.007182	9.863457	0.049429	0.087933	-0.033841
+13.868089	-0.033517	0.021546	9.808394	0.048496	0.090730	-0.036905
+13.869088	0.028729	0.011970	9.762907	0.047297	0.092596	-0.037571
+13.870090	-0.011970	-0.040699	9.789242	0.045432	0.089265	-0.035706
+13.871089	-0.019152	-0.047881	9.803606	0.046764	0.085934	-0.036239
+13.872010	-0.011970	-0.016758	9.813182	0.047164	0.085002	-0.037038
+13.873067	0.009576	0.007182	9.794030	0.047963	0.085534	-0.035573
+13.874098	-0.033517	0.019152	9.772483	0.047031	0.087400	-0.036106
+13.875090	-0.033517	-0.026334	9.726997	0.045698	0.091796	-0.033974
+13.876089	0.002394	-0.011970	9.794030	0.045299	0.091130	-0.033441
+13.877090	-0.021546	-0.040699	9.806000	0.046498	0.086467	-0.034640
+13.878090	0.016758	-0.021546	9.815576	0.047164	0.086734	-0.038371
+13.879089	0.014364	-0.009576	9.817970	0.045965	0.086467	-0.035972
+13.880020	0.009576	-0.009576	9.806000	0.044100	0.091130	-0.033841
+13.881051	0.014364	-0.007182	9.877821	0.043833	0.091263	-0.034240
+13.882038	0.033517	-0.047881	9.865851	0.045165	0.088599	-0.034240
+13.883086	0.014364	-0.009576	9.861063	0.047031	0.085668	-0.038504
+13.884089	-0.007182	0.007182	9.806000	0.048096	0.086600	-0.039836
+13.885020	0.045487	0.021546	9.762907	0.047430	0.088998	-0.036772
+13.886029	0.004788	0.016758	9.784454	0.046498	0.087533	-0.034507
+13.887089	-0.035911	0.045487	9.770089	0.047830	0.089931	-0.036239
+13.888087	-0.004788	0.016758	9.844305	0.047564	0.089931	-0.040103
+13.889086	-0.011970	-0.026334	9.770089	0.046098	0.089265	-0.038104
+13.890090	-0.035911	0.016758	9.758119	0.044632	0.088199	-0.033175
+13.891032	-0.076609	-0.026334	9.784454	0.047830	0.089132	-0.030910
+13.892085	0.000000	0.016758	9.784454	0.046498	0.088732	-0.031842
+13.893089	-0.007182	-0.033517	9.801212	0.043700	0.090331	-0.034907
+13.894089	0.050275	-0.031123	9.817970	0.044899	0.088865	-0.036505
+13.895089	0.093368	0.014364	9.849093	0.048230	0.088199	-0.038504
+13.896087	0.047881	-0.031123	9.801212	0.045832	0.087133	-0.037038
+13.897029	0.043093	-0.047881	9.760513	0.045032	0.085801	-0.033574
+13.898029	0.031123	-0.019152	9.885003	0.047430	0.088066	-0.036106
+13.899001	0.038305	0.021546	9.820364	0.046364	0.090864	-0.036372
+13.900028	0.011970	0.009576	9.755725	0.046498	0.088998	-0.035040
+13.901013	-0.045487	-0.074215	9.815576	0.047297	0.088199	-0.035306
+13.902064	-0.014364	-0.057457	9.832334	0.046897	0.089931	-0.037172
+13.903109	0.011970	-0.004788	9.832334	0.047164	0.089531	-0.041701
+13.904109	-0.071821	0.038305	9.834729	0.046631	0.086734	-0.037438
+13.905113	-0.055063	0.043093	9.779666	0.047164	0.086867	-0.033175
+13.906114	-0.031123	-0.045487	9.707844	0.045299	0.086201	-0.032375
+13.907110	-0.033517	-0.026334	9.786848	0.043966	0.084335	-0.038637
+13.908110	-0.031123	-0.004788	9.839517	0.046498	0.087666	-0.039836
+13.909066	-0.031123	0.031123	9.889792	0.050361	0.089931	-0.035440
+13.910077	0.040699	0.050275	9.767695	0.050761	0.089531	-0.038104
+13.911115	0.069427	-0.014364	9.738967	0.045565	0.087799	-0.038770
+13.912110	0.035911	0.000000	9.762907	0.045299	0.087266	-0.039570
+13.913110	0.028729	0.026334	9.880215	0.046231	0.086467	-0.036772
+13.914115	0.019152	0.074215	9.770089	0.048363	0.087000	-0.035306
+13.915113	-0.007182	0.021546	9.791636	0.049162	0.088066	-0.036772
+13.916110	0.004788	0.026334	9.753331	0.048230	0.086734	-0.036505
+13.917067	0.004788	0.071821	9.755725	0.048629	0.088332	-0.035839
+13.918038	0.002394	-0.026334	9.791636	0.047697	0.088332	-0.036372
+13.919037	0.031123	-0.019152	9.841911	0.047830	0.084868	-0.036106
+13.920012	0.009576	-0.004788	9.808394	0.047963	0.085268	-0.034907
+13.921041	-0.047881	-0.007182	9.815576	0.047297	0.087400	-0.033574
+13.921970	0.016758	-0.026334	9.777271	0.049429	0.090864	-0.031842
+13.923045	0.028729	0.043093	9.753331	0.049296	0.089265	-0.035173
+13.924024	0.002394	0.021546	9.789242	0.045432	0.085801	-0.036772
+13.925050	0.031123	-0.023940	9.873033	0.044233	0.085401	-0.037571
+13.926051	0.052669	-0.050275	9.868245	0.046231	0.086600	-0.035306
+13.927049	0.007182	0.021546	9.772483	0.046231	0.088199	-0.034640
+13.928044	-0.047881	0.009576	9.808394	0.045965	0.090064	-0.034907
+13.929047	-0.026334	0.004788	9.789242	0.047430	0.088199	-0.035040
+13.929995	0.033517	-0.007182	9.755725	0.047031	0.086334	-0.035839
+13.931017	0.035911	-0.035911	9.865851	0.047697	0.087400	-0.037038
+13.932001	-0.002394	0.021546	9.908944	0.048629	0.088865	-0.032775
+13.933050	0.007182	0.033517	9.882609	0.047963	0.089398	-0.031309
+13.934053	0.019152	0.000000	9.875427	0.047564	0.088066	-0.033708
+13.935014	-0.014364	-0.035911	9.724603	0.048363	0.084735	-0.032908
+13.936031	0.038305	-0.004788	9.784454	0.045299	0.083669	-0.033708
+13.937050	0.000000	-0.045487	9.808394	0.046231	0.087533	-0.036639
+13.938054	-0.023940	-0.007182	9.846699	0.047031	0.087533	-0.033441
+13.939048	-0.009576	0.028729	9.853881	0.046631	0.089265	-0.035972
+13.940053	0.021546	0.014364	9.789242	0.046631	0.090331	-0.039836
+13.941035	-0.019152	-0.019152	9.700662	0.045299	0.089132	-0.040236
+13.942067	0.021546	-0.055063	9.885003	0.044100	0.087666	-0.037704
+13.943051	0.009576	-0.019152	9.837123	0.046098	0.088998	-0.034640
+13.944054	-0.004788	-0.026334	9.810788	0.046897	0.087799	-0.035706
+13.945052	-0.011970	-0.026334	9.875427	0.048496	0.085801	-0.036772
+13.946019	-0.026334	-0.069427	9.873033	0.050361	0.087266	-0.036505
+13.947026	0.062245	-0.047881	9.743755	0.051294	0.088466	-0.037438
+13.948049	0.045487	-0.009576	9.791636	0.049429	0.086600	-0.035573
+13.948992	-0.067033	-0.014364	9.796424	0.046364	0.086334	-0.035573
+13.950046	-0.047881	0.028729	9.794030	0.045032	0.086600	-0.039303
+13.951049	0.028729	-0.004788	9.849093	0.047164	0.086067	-0.039703
+13.952008	-0.009576	-0.055063	9.810788	0.044899	0.088199	-0.034773
+13.953072	0.004788	-0.002394	9.746149	0.045565	0.090997	-0.034374
+13.953991	-0.023940	0.019152	9.782060	0.047297	0.091263	-0.035306
+13.955050	0.019152	0.000000	9.841911	0.047297	0.086867	-0.035306
+13.956051	0.035911	-0.009576	9.885003	0.044899	0.086734	-0.036772
+13.957050	0.002394	0.011970	9.868245	0.046098	0.087799	-0.036905
+13.958052	0.019152	-0.040699	9.827546	0.045832	0.087400	-0.035573
+13.959049	0.016758	0.007182	9.753331	0.047031	0.088199	-0.035573
+13.960051	0.052669	-0.002394	9.782060	0.046897	0.087133	-0.035040
+13.961050	0.069427	-0.009576	9.820364	0.047564	0.087400	-0.035839
+13.962030	0.086186	-0.031123	9.755725	0.047430	0.087666	-0.038237
+13.963066	0.059851	0.002394	9.825152	0.047697	0.087000	-0.037172
+13.964050	0.050275	-0.004788	9.827546	0.045565	0.086334	-0.036372
+13.965016	0.033517	-0.009576	9.808394	0.045299	0.088332	-0.036505
+13.966052	-0.038305	-0.035911	9.806000	0.045965	0.087799	-0.037172
+13.967044	0.004788	0.016758	9.798818	0.047430	0.088332	-0.038237
+13.968050	-0.031123	0.009576	9.794030	0.047697	0.088199	-0.035706
+13.969049	-0.019152	0.021546	9.829940	0.046364	0.088865	-0.037038
+13.970001	0.021546	0.028729	9.808394	0.045832	0.089798	-0.035839
+13.971049	-0.011970	0.047881	9.863457	0.046631	0.087666	-0.037971
+13.972032	0.009576	0.016758	9.849093	0.047564	0.086734	-0.035839
+13.973073	0.033517	0.074215	9.825152	0.046631	0.086734	-0.033708
+13.974053	-0.021546	0.021546	9.844305	0.045698	0.087266	-0.034640
+13.975043	-0.071821	-0.021546	9.844305	0.048230	0.087799	-0.033574
+13.976049	0.002394	0.016758	9.851487	0.051028	0.089665	-0.035040
+13.977051	0.007182	-0.007182	9.770089	0.050761	0.090997	-0.033841
+13.978053	0.026334	-0.009576	9.736573	0.048363	0.087799	-0.034107
+13.979052	0.028729	0.011970	9.849093	0.046231	0.089132	-0.036106
+13.980043	-0.007182	-0.019152	9.825152	0.044899	0.088732	-0.037971
+13.981049	0.028729	-0.050275	9.700662	0.045698	0.087933	-0.037571
+13.982053	-0.050275	-0.062245	9.717420	0.045165	0.087666	-0.035573
+13.983006	-0.021546	-0.038305	9.796424	0.045698	0.087533	-0.029977
+13.984071	0.028729	-0.038305	9.813182	0.049029	0.089398	-0.031443
+13.985046	-0.047881	-0.026334	9.851487	0.048363	0.088732	-0.035440
+13.986072	-0.050275	0.009576	9.837123	0.048096	0.085534	-0.037438
+13.987049	0.011970	0.028729	9.861063	0.046764	0.086867	-0.038371
+13.988045	0.047881	0.028729	9.928096	0.047297	0.089531	-0.037172
+13.989052	0.016758	-0.004788	9.923308	0.046498	0.088066	-0.036505
+13.990051	-0.004788	-0.021546	9.839517	0.046364	0.086734	-0.037971
+13.991048	-0.007182	0.035911	9.832334	0.046897	0.085801	-0.036772
+13.992051	-0.004788	-0.009576	9.794030	0.047697	0.087400	-0.034240
+13.993033	0.000000	-0.009576	9.794030	0.048629	0.090997	-0.036639
+13.994058	-0.009576	0.000000	9.882609	0.048896	0.088599	-0.037838
+13.995049	0.028729	-0.009576	9.834729	0.047564	0.087533	-0.038904
+13.996049	0.000000	0.016758	9.741361	0.047430	0.088466	-0.038104
+13.996989	-0.038305	0.014364	9.837123	0.048096	0.089531	-0.032775
+13.998053	0.019152	-0.004788	9.885003	0.048230	0.087266	-0.033574
+13.998984	0.033517	-0.038305	9.861063	0.047031	0.087666	-0.041168
+13.999985	0.019152	0.007182	9.815576	0.046364	0.088066	-0.040636
+14.001050	0.043093	-0.004788	9.803606	0.046631	0.086734	-0.037172
+14.002051	-0.009576	-0.007182	9.736573	0.048096	0.085135	-0.037571
+14.003051	0.002394	0.019152	9.760513	0.049029	0.088332	-0.035972
+14.004036	-0.009576	-0.007182	9.753331	0.048763	0.090997	-0.037704
+14.005068	0.045487	0.000000	9.803606	0.046764	0.089398	-0.038237
+14.006053	-0.004788	0.028729	9.791636	0.046364	0.089132	-0.037038
+14.007051	0.067033	0.014364	9.791636	0.045965	0.089132	-0.036639
+14.008049	0.086186	0.004788	9.832334	0.043700	0.088599	-0.037305
+14.009015	-0.011970	0.028729	9.827546	0.044632	0.085534	-0.037971
+14.010053	-0.076609	0.033517	9.784454	0.047031	0.086867	-0.037704
+14.011049	-0.026334	0.055063	9.726997	0.047564	0.084602	-0.035440
+14.012049	-0.004788	-0.031123	9.774877	0.047297	0.086201	-0.032908
+14.013013	0.014364	-0.007182	9.834729	0.047297	0.088865	-0.034240
+14.014052	0.079003	0.026334	9.810788	0.047697	0.089798	-0.035306
+14.015018	0.026334	-0.055063	9.779666	0.047031	0.088332	-0.036505
+14.016053	0.090974	-0.011970	9.679116	0.045698	0.087400	-0.037305
+14.017049	0.019152	0.016758	9.827546	0.047031	0.086867	-0.040103
+14.018021	-0.011970	0.009576	9.820364	0.047830	0.088332	-0.038504
+14.019025	-0.040699	-0.009576	9.743755	0.047697	0.087799	-0.034374
+14.020042	0.038305	-0.016758	9.734179	0.044766	0.089265	-0.033574
+14.021043	0.000000	-0.004788	9.827546	0.044899	0.090064	-0.036239
+14.022034	0.019152	0.067033	9.908944	0.046897	0.087266	-0.036505
+14.023042	-0.033517	0.009576	9.803606	0.046498	0.084868	-0.033841
+14.024043	-0.035911	-0.035911	9.822758	0.046631	0.088332	-0.032242
+14.025054	-0.007182	-0.007182	9.875427	0.047830	0.088865	-0.033041
+14.026065	0.016758	-0.045487	9.913732	0.047430	0.087799	-0.033841
+14.027047	0.009576	0.016758	9.765301	0.047963	0.086867	-0.034640
+14.028042	0.007182	0.057457	9.731785	0.047297	0.084602	-0.034773
+14.029042	0.021546	-0.014364	9.789242	0.047430	0.086201	-0.036905
+14.030052	0.016758	-0.016758	9.789242	0.043700	0.088599	-0.036905
+14.031108	0.007182	0.014364	9.815576	0.044366	0.087666	-0.037438
+14.032110	0.023940	-0.045487	9.801212	0.046098	0.085801	-0.037971
+14.033051	0.033517	-0.031123	9.834729	0.047697	0.085801	-0.035706
+14.034084	0.052669	-0.047881	9.844305	0.045432	0.087799	-0.034773
+14.035047	-0.009576	-0.045487	9.810788	0.045165	0.089798	-0.034640
+14.036102	-0.011970	0.026334	9.822758	0.045165	0.091263	-0.037305
+14.037048	0.026334	0.067033	9.762907	0.045965	0.089665	-0.033841
+14.038110	0.016758	0.047881	9.755725	0.046631	0.088732	-0.034240
+14.039021	0.050275	0.004788	9.767695	0.045965	0.088599	-0.036905
+14.040108	-0.045487	0.007182	9.913732	0.046231	0.089265	-0.037172
+14.041109	-0.045487	-0.009576	9.839517	0.047164	0.088332	-0.035573
+14.042109	-0.035911	-0.014364	9.753331	0.047297	0.089265	-0.035173
+14.043106	-0.004788	-0.021546	9.782060	0.047031	0.088599	-0.040236
+14.044063	0.038305	-0.014364	9.765301	0.048230	0.089132	-0.038237
+14.045046	0.016758	0.011970	9.738967	0.046364	0.087000	-0.032908
+14.045993	0.059851	-0.047881	9.837123	0.047697	0.088466	-0.033175
+14.047060	-0.040699	-0.007182	9.803606	0.047031	0.087933	-0.033175
+14.048044	-0.016758	0.009576	9.851487	0.045832	0.088066	-0.033574
+14.049076	0.023940	0.021546	9.832334	0.047031	0.088732	-0.039969
+14.050011	0.055063	0.026334	9.803606	0.047430	0.088998	-0.037971
+14.051021	0.031123	0.002394	9.777271	0.045432	0.088732	-0.038904
+14.052108	-0.040699	-0.007182	9.815576	0.045832	0.084335	-0.037438
+14.053109	-0.062245	-0.009576	9.880215	0.046098	0.085534	-0.034640
+14.054063	-0.011970	-0.016758	9.928096	0.047031	0.087799	-0.038637
+14.055078	-0.019152	-0.035911	9.849093	0.046897	0.087266	-0.038904
+14.056107	-0.028729	0.016758	9.738967	0.047963	0.087133	-0.038904
+14.057111	0.021546	0.028729	9.724603	0.046897	0.086334	-0.036772
+14.058051	0.023940	0.002394	9.856275	0.046631	0.089265	-0.035573
+14.059106	0.055063	0.002394	9.841911	0.047031	0.090597	-0.033841
+14.060039	0.071821	0.026334	9.801212	0.049962	0.089931	-0.035573
+14.061107	0.000000	0.000000	9.794030	0.051294	0.087666	-0.037704
+14.062052	-0.023940	0.007182	9.832334	0.048363	0.088732	-0.038237
+14.063064	0.057457	0.000000	9.813182	0.048096	0.087799	-0.036905
+14.064102	0.064639	-0.031123	9.715026	0.048096	0.086867	-0.037172
+14.065054	0.000000	-0.033517	9.777271	0.046364	0.087000	-0.037838
+14.066110	-0.038305	-0.011970	9.825152	0.047297	0.088332	-0.037704
+14.067110	-0.026334	-0.031123	9.873033	0.048363	0.087666	-0.037704
+14.068050	0.007182	-0.009576	9.873033	0.047963	0.086867	-0.037704
+14.069109	-0.033517	-0.021546	9.899368	0.045432	0.087533	-0.034907
+14.070072	-0.047881	-0.050275	9.885003	0.043700	0.089132	-0.036505
+14.071035	-0.023940	-0.016758	9.808394	0.043167	0.091130	-0.039303
+14.072054	-0.007182	-0.055063	9.750937	0.046364	0.088998	-0.038904
+14.073067	0.007182	-0.035911	9.806000	0.048363	0.087799	-0.035972
+14.074110	-0.021546	0.007182	9.796424	0.048896	0.087666	-0.036772
+14.075106	-0.055063	0.023940	9.873033	0.045565	0.087933	-0.035173
+14.076107	-0.055063	-0.009576	9.868245	0.045698	0.088732	-0.035972
+14.077030	0.074215	0.002394	9.777271	0.048629	0.086734	-0.031842
+14.078010	0.050275	0.021546	9.789242	0.047297	0.088865	-0.034507
+14.079008	0.014364	-0.028729	9.743755	0.042767	0.088466	-0.039836
+14.080043	0.007182	-0.059851	9.789242	0.041435	0.088599	-0.039570
+14.081044	-0.040699	0.050275	9.832334	0.045432	0.086734	-0.036905
+14.082033	-0.011970	0.014364	9.916126	0.046764	0.086334	-0.035706
+14.083037	0.009576	0.031123	9.877821	0.046098	0.086600	-0.038904
+14.084042	0.050275	0.009576	9.870639	0.046631	0.086067	-0.037038
+14.085043	-0.007182	-0.002394	9.837123	0.046498	0.087933	-0.034907
+14.086111	0.000000	0.007182	9.885003	0.045165	0.089132	-0.033041
+14.087112	-0.007182	-0.033517	9.794030	0.045299	0.088865	-0.030643
+14.088108	-0.021546	-0.055063	9.772483	0.047830	0.090730	-0.035306
+14.089110	0.014364	-0.059851	9.834729	0.047564	0.091530	-0.039303
+14.090047	-0.011970	0.004788	9.839517	0.046631	0.090198	-0.036505
+14.091050	0.033517	-0.031123	9.885003	0.046098	0.086867	-0.031043
+14.092056	0.028729	-0.047881	9.829940	0.045698	0.087666	-0.033041
+14.093098	0.038305	-0.050275	9.865851	0.046897	0.088066	-0.033708
+14.094052	0.071821	-0.014364	9.734179	0.046764	0.086201	-0.033974
+14.095047	0.035911	-0.059851	9.758119	0.047164	0.086734	-0.037438
+14.096108	0.000000	0.002394	9.849093	0.047697	0.089132	-0.037172
+14.097107	0.064639	0.035911	9.846699	0.047963	0.087400	-0.035706
+14.098042	0.040699	0.086186	9.798818	0.046897	0.086600	-0.034640
+14.099083	0.023940	0.000000	9.791636	0.047297	0.087799	-0.037038
+14.100047	0.035911	-0.052669	9.789242	0.046631	0.090864	-0.034773
+14.101066	-0.023940	0.002394	9.772483	0.047031	0.090064	-0.034773
+14.102045	-0.016758	0.009576	9.755725	0.046764	0.087533	-0.036639
+14.103105	-0.050275	-0.014364	9.868245	0.046098	0.085002	-0.035972
+14.104108	0.023940	-0.016758	9.861063	0.045698	0.086467	-0.037838
+14.105108	-0.007182	-0.011970	9.813182	0.044499	0.086467	-0.034107
+14.106110	-0.038305	0.000000	9.856275	0.046631	0.087666	-0.034773
+14.107105	0.035911	0.007182	9.820364	0.049695	0.086734	-0.038637
+14.108105	0.079003	0.016758	9.806000	0.049429	0.086467	-0.039170
+14.109046	0.040699	0.028729	9.746149	0.047430	0.087000	-0.038904
+14.110049	0.043093	-0.033517	9.798818	0.045832	0.088066	-0.037971
+14.111063	0.081397	-0.021546	9.858669	0.046631	0.089798	-0.034640
+14.112104	0.016758	-0.031123	9.758119	0.049429	0.091397	-0.035440
+14.113051	0.052669	-0.016758	9.758119	0.049562	0.088865	-0.035306
+14.114052	0.016758	0.007182	9.722208	0.047031	0.087799	-0.035440
+14.115107	-0.043093	0.021546	9.762907	0.045565	0.085934	-0.038371
+14.116108	0.011970	0.026334	9.813182	0.047164	0.086067	-0.039037
+14.117024	0.019152	-0.019152	9.877821	0.045698	0.085668	-0.036505
+14.118031	0.004788	0.043093	9.846699	0.045565	0.087000	-0.036639
+14.119107	-0.064639	0.009576	9.777271	0.047031	0.088466	-0.036639
+14.120057	-0.035911	-0.009576	9.877821	0.049162	0.085934	-0.036505
+14.121106	-0.021546	-0.014364	9.750937	0.048896	0.084202	-0.036239
+14.122111	0.000000	-0.026334	9.789242	0.048096	0.085934	-0.035440
+14.123050	0.002394	0.016758	9.784454	0.046498	0.085534	-0.032775
+14.124109	0.004788	-0.014364	9.784454	0.045832	0.085668	-0.032375
+14.125105	0.043093	-0.043093	9.827546	0.048363	0.086734	-0.038637
+14.126111	0.033517	0.000000	9.806000	0.048363	0.090997	-0.040103
+14.127107	-0.016758	-0.007182	9.779666	0.049562	0.093928	-0.036106
+14.128105	0.007182	-0.040699	9.753331	0.048096	0.090597	-0.035040
+14.129041	-0.038305	-0.033517	9.849093	0.046364	0.086734	-0.033974
+14.130070	0.050275	-0.031123	9.801212	0.045032	0.088066	-0.035972
+14.131109	0.026334	-0.035911	9.758119	0.043567	0.086600	-0.033708
+14.132107	0.016758	-0.026334	9.813182	0.044632	0.085534	-0.036639
+14.133024	0.050275	0.016758	9.784454	0.045299	0.085668	-0.038237
+14.134062	-0.004788	-0.009576	9.863457	0.045565	0.089132	-0.041435
+14.135036	-0.007182	0.014364	9.880215	0.044899	0.089398	-0.039037
+14.136037	-0.038305	-0.028729	9.803606	0.046098	0.089665	-0.035706
+14.137019	0.026334	0.031123	9.832334	0.047564	0.089265	-0.037172
+14.138044	0.023940	-0.009576	9.880215	0.044766	0.088466	-0.034640
+14.139067	0.011970	-0.021546	9.856275	0.045032	0.088199	-0.035839
+14.140046	0.000000	-0.016758	9.827546	0.047697	0.088998	-0.035440
+14.141106	0.040699	-0.004788	9.837123	0.047564	0.088466	-0.036905
+14.142114	0.040699	-0.011970	9.803606	0.047697	0.089665	-0.037838
+14.143040	-0.009576	0.016758	9.815576	0.046098	0.090331	-0.033974
+14.144034	-0.009576	-0.007182	9.789242	0.047564	0.088732	-0.033708
+14.145108	-0.019152	-0.007182	9.853881	0.046498	0.086201	-0.033574
+14.146113	-0.038305	0.004788	9.782060	0.046364	0.086734	-0.036905
+14.147105	0.021546	0.002394	9.827546	0.048496	0.087133	-0.039037
+14.148107	0.064639	-0.021546	9.813182	0.049962	0.087400	-0.035972
+14.149107	0.045487	-0.059851	9.750937	0.050761	0.086734	-0.034107
+14.150052	0.031123	-0.014364	9.846699	0.047164	0.089398	-0.035306
+14.151103	0.000000	0.000000	9.856275	0.046897	0.089931	-0.038504
+14.152109	-0.002394	-0.009576	9.882609	0.048763	0.089665	-0.038237
+14.153046	0.004788	-0.043093	9.786848	0.049296	0.087400	-0.034374
+14.154111	-0.035911	0.023940	9.861063	0.047430	0.086734	-0.036106
+14.155109	0.031123	0.004788	9.829940	0.046897	0.089265	-0.034640
+14.156106	0.055063	0.011970	9.755725	0.045965	0.087533	-0.038904
+14.157105	0.009576	0.033517	9.777271	0.044233	0.090064	-0.041168
+14.158080	-0.021546	0.023940	9.863457	0.045832	0.089798	-0.038371
+14.159044	0.067033	-0.004788	9.808394	0.045299	0.088066	-0.035573
+14.160072	0.047881	0.019152	9.758119	0.047830	0.085135	-0.034907
+14.161108	0.002394	0.033517	9.839517	0.047031	0.085801	-0.034907
+14.162110	0.067033	0.021546	9.829940	0.044766	0.088066	-0.036639
+14.163100	0.021546	0.016758	9.784454	0.043567	0.089531	-0.037838
+14.164093	-0.026334	0.009576	9.849093	0.045965	0.090730	-0.036372
+14.165103	0.014364	0.028729	9.734179	0.047430	0.088199	-0.035173
+14.166048	-0.026334	-0.007182	9.738967	0.047031	0.084469	-0.039303
+14.167107	0.002394	0.004788	9.762907	0.047697	0.085801	-0.038770
+14.168034	-0.004788	-0.023940	9.738967	0.045832	0.087266	-0.036239
+14.169022	0.026334	0.019152	9.755725	0.046764	0.087799	-0.035306
+14.170058	0.021546	0.023940	9.782060	0.045165	0.086334	-0.037704
+14.171107	0.033517	0.045487	9.748543	0.047697	0.088466	-0.037305
+14.172107	0.028729	0.007182	9.719814	0.049029	0.087799	-0.035839
+14.173107	-0.023940	-0.007182	9.734179	0.048096	0.087933	-0.038637
+14.174112	0.011970	0.016758	9.791636	0.047430	0.087933	-0.040103
+14.175105	0.038305	0.002394	9.784454	0.045432	0.088599	-0.037704
+14.176106	-0.021546	0.045487	9.827546	0.044233	0.087000	-0.035573
+14.177114	0.067033	0.035911	9.832334	0.046764	0.088199	-0.036505
+14.178046	0.090974	0.050275	9.808394	0.048629	0.086734	-0.035573
+14.179050	-0.023940	-0.023940	9.746149	0.047297	0.087000	-0.035972
+14.180102	-0.033517	-0.045487	9.798818	0.046631	0.087133	-0.034773
+14.181110	0.055063	-0.002394	9.868245	0.047031	0.089265	-0.034507
+14.182068	-0.016758	0.028729	9.832334	0.046231	0.090198	-0.032775
+14.183107	0.038305	0.016758	9.784454	0.046231	0.089798	-0.033441
+14.184108	0.069427	0.016758	9.784454	0.047031	0.088865	-0.036106
+14.185023	0.035911	0.019152	9.786848	0.048096	0.085934	-0.036239
+14.186111	0.014364	0.002394	9.734179	0.051028	0.086334	-0.033708
+14.187061	-0.023940	0.016758	9.736573	0.049695	0.088199	-0.032908
+14.188099	0.016758	-0.052669	9.794030	0.047031	0.087933	-0.033308
+14.189107	0.000000	-0.043093	9.882609	0.047697	0.086867	-0.036239
+14.190055	0.014364	-0.014364	9.837123	0.046098	0.085268	-0.036106
+14.191040	0.014364	-0.021546	9.810788	0.047031	0.088599	-0.037571
+14.192040	-0.014364	-0.059851	9.832334	0.047830	0.090198	-0.038371
+14.193042	-0.014364	-0.038305	9.827546	0.046364	0.089798	-0.037704
+14.194013	0.011970	0.000000	9.853881	0.047564	0.088865	-0.035040
+14.195044	0.033517	-0.050275	9.846699	0.048363	0.088998	-0.036239
+14.196041	0.069427	-0.031123	9.777271	0.048896	0.088332	-0.036772
+14.197041	0.014364	-0.062245	9.789242	0.048230	0.086467	-0.036639
+14.198051	-0.021546	-0.016758	9.777271	0.047963	0.088466	-0.037971
+14.199075	-0.023940	0.074215	9.801212	0.046231	0.090597	-0.039703
+14.200007	-0.059851	-0.007182	9.827546	0.047164	0.089132	-0.039703
+14.201043	-0.023940	-0.009576	9.820364	0.045832	0.086201	-0.037438
+14.202045	-0.023940	0.000000	9.865851	0.046098	0.087799	-0.035839
+14.203104	-0.028729	-0.004788	9.806000	0.047031	0.089265	-0.037305
+14.204106	0.009576	0.026334	9.770089	0.046098	0.088732	-0.034374
+14.205104	-0.009576	0.043093	9.846699	0.045299	0.087000	-0.033574
+14.206108	-0.002394	0.050275	9.899368	0.046098	0.087000	-0.035972
+14.207105	-0.028729	0.016758	9.786848	0.045565	0.086734	-0.038371
+14.208057	-0.026334	-0.002394	9.760513	0.045565	0.088599	-0.037038
+14.209098	-0.014364	0.002394	9.825152	0.046764	0.088332	-0.037172
+14.210047	0.040699	0.035911	9.856275	0.046897	0.086734	-0.036905
+14.211106	0.064639	0.028729	9.815576	0.047031	0.086734	-0.038504
+14.212062	0.016758	-0.004788	9.882609	0.048230	0.089132	-0.034907
+14.213107	0.033517	-0.004788	9.829940	0.048363	0.088332	-0.036372
+14.214066	0.040699	-0.016758	9.748543	0.049429	0.084469	-0.035839
+14.215109	0.050275	-0.004788	9.729391	0.049029	0.084069	-0.037971
+14.216107	0.009576	-0.011970	9.813182	0.047164	0.086201	-0.035839
+14.217018	-0.031123	-0.021546	9.873033	0.045965	0.087533	-0.035306
+14.218044	0.004788	-0.043093	9.767695	0.044100	0.089798	-0.038637
+14.219036	0.059851	-0.033517	9.767695	0.045698	0.088732	-0.038371
+14.220021	-0.016758	0.014364	9.784454	0.047430	0.089798	-0.038504
+14.221005	0.019152	0.009576	9.772483	0.047297	0.092329	-0.037305
+14.222038	0.043093	0.014364	9.820364	0.047830	0.092596	-0.037704
+14.223031	-0.002394	-0.033517	9.817970	0.047963	0.091130	-0.034907
+14.224034	0.043093	-0.064639	9.738967	0.049962	0.087933	-0.036905
+14.225005	0.004788	0.009576	9.829940	0.051161	0.087666	-0.035706
+14.225995	0.019152	0.019152	9.810788	0.046897	0.088066	-0.034507
+14.227010	-0.067033	0.016758	9.794030	0.043700	0.089398	-0.038504
+14.228007	-0.014364	0.035911	9.786848	0.043567	0.089665	-0.036772
+14.229015	-0.033517	-0.014364	9.813182	0.044632	0.088599	-0.035040
+14.230017	0.033517	0.002394	9.779666	0.049029	0.088599	-0.035040
+14.231036	0.000000	0.016758	9.767695	0.049828	0.088066	-0.036505
+14.232035	0.062245	-0.057457	9.765301	0.047564	0.087933	-0.035306
+14.233035	0.069427	-0.014364	9.791636	0.045965	0.089132	-0.036372
+14.234038	-0.038305	0.050275	9.894580	0.045832	0.088998	-0.035839
+14.235019	0.002394	-0.019152	9.892186	0.047297	0.087533	-0.036905
+14.236006	0.031123	0.000000	9.846699	0.048230	0.086067	-0.034907
+14.237032	-0.011970	-0.011970	9.827546	0.048230	0.087799	-0.036239
+14.237955	0.031123	-0.007182	9.858669	0.047564	0.087133	-0.037305
+14.238966	-0.011970	-0.019152	9.844305	0.047297	0.087266	-0.036639
+14.239970	0.011970	-0.011970	9.784454	0.046098	0.088865	-0.034773
+14.240980	0.055063	-0.067033	9.806000	0.045698	0.087933	-0.034907
+14.241972	0.071821	-0.002394	9.794030	0.045032	0.088732	-0.035040
+14.242968	0.076609	0.000000	9.777271	0.045698	0.090597	-0.039969
+14.243966	-0.035911	-0.014364	9.779666	0.046231	0.089398	-0.041835
+14.244974	-0.031123	-0.059851	9.729391	0.046631	0.086600	-0.038637
+14.246415	-0.028729	-0.057457	9.762907	0.047031	0.087000	-0.035040
+14.246972	0.000000	-0.026334	9.765301	0.048496	0.088865	-0.032375
+14.248359	0.004788	-0.007182	9.791636	0.049828	0.087400	-0.036106
+14.248974	0.009576	-0.055063	9.743755	0.048629	0.088199	-0.038904
+14.249966	-0.011970	0.016758	9.810788	0.045832	0.088066	-0.039436
+14.250983	-0.028729	-0.011970	9.870639	0.044499	0.088998	-0.035706
+14.251981	-0.031123	-0.009576	9.782060	0.045565	0.086867	-0.036639
+14.252970	-0.016758	0.009576	9.803606	0.047031	0.087933	-0.037438
+14.253985	-0.026334	0.028729	9.758119	0.047297	0.087000	-0.033841
+14.254983	-0.038305	-0.019152	9.746149	0.048496	0.086867	-0.035306
+14.255997	-0.033517	-0.004788	9.758119	0.048496	0.089531	-0.035839
+14.256977	-0.014364	0.026334	9.832334	0.048230	0.087533	-0.037172
+14.257975	-0.004788	-0.011970	9.841911	0.048629	0.088199	-0.037038
+14.258974	0.031123	0.028729	9.789242	0.047963	0.089531	-0.037838
+14.259962	0.011970	0.009576	9.822758	0.047031	0.090730	-0.038504
+14.260977	0.028729	-0.028729	9.789242	0.047031	0.090997	-0.035173
+14.261958	0.023940	-0.035911	9.743755	0.047830	0.089931	-0.034773
+14.262971	-0.019152	-0.043093	9.817970	0.046631	0.088732	-0.034240
+14.263963	0.023940	0.000000	9.856275	0.047031	0.086600	-0.037305
+14.264938	-0.007182	-0.002394	9.817970	0.047430	0.085668	-0.036639
+14.265960	0.016758	0.035911	9.758119	0.047430	0.085934	-0.035040
+14.266962	0.021546	0.023940	9.750937	0.048096	0.086334	-0.034640
+14.267963	-0.011970	0.057457	9.841911	0.049562	0.086600	-0.037172
+14.268955	0.004788	0.021546	9.851487	0.048763	0.087000	-0.040502
+14.269939	0.007182	0.009576	9.822758	0.048230	0.086734	-0.039570
+14.270939	0.011970	0.038305	9.868245	0.045165	0.087400	-0.037172
+14.271954	-0.009576	0.011970	9.856275	0.043833	0.090198	-0.036239
+14.272941	0.019152	-0.033517	9.841911	0.044499	0.086734	-0.032908
+14.273942	-0.026334	-0.052669	9.877821	0.046631	0.085135	-0.035306
+14.274942	0.011970	-0.019152	9.786848	0.046498	0.087133	-0.038371
+14.275940	0.011970	-0.023940	9.784454	0.048230	0.088865	-0.036106
+14.276941	0.069427	0.023940	9.832334	0.049562	0.089931	-0.035306
+14.277941	0.009576	-0.043093	9.851487	0.047697	0.087266	-0.037038
+14.278991	0.057457	-0.052669	9.796424	0.048096	0.086067	-0.037971
+14.279949	0.021546	-0.007182	9.827546	0.047164	0.086467	-0.036239
+14.280990	0.038305	0.028729	9.856275	0.045565	0.086067	-0.034374
+14.281976	0.002394	0.002394	9.846699	0.046231	0.088199	-0.037571
+14.282995	-0.031123	0.009576	9.851487	0.050228	0.089798	-0.040369
+14.283995	0.002394	-0.011970	9.853881	0.049296	0.087533	-0.038770
+14.284992	-0.014364	0.011970	9.846699	0.048629	0.087933	-0.036639
+14.285967	-0.045487	-0.002394	9.820364	0.045165	0.090730	-0.035706
+14.286996	-0.023940	-0.064639	9.777271	0.043700	0.089132	-0.035972
+14.288046	0.019152	-0.050275	9.789242	0.046631	0.087133	-0.036772
+14.289047	0.011970	0.023940	9.820364	0.047697	0.088865	-0.038237
+14.290018	-0.007182	0.038305	9.777271	0.051694	0.088599	-0.033308
+14.291041	0.035911	-0.002394	9.748543	0.049562	0.087000	-0.035040
+14.292047	0.035911	-0.038305	9.794030	0.049562	0.085801	-0.036772
+14.293028	0.043093	-0.019152	9.729391	0.048363	0.087000	-0.033441
+14.293974	-0.014364	0.040699	9.784454	0.045165	0.089665	-0.033175
+14.294987	-0.002394	-0.016758	9.798818	0.046631	0.091263	-0.032375
+14.295967	0.007182	0.023940	9.777271	0.045832	0.088865	-0.031709
+14.296993	0.011970	0.043093	9.806000	0.045965	0.087666	-0.035040
+14.297957	-0.004788	0.011970	9.851487	0.046364	0.087266	-0.037305
+14.298979	-0.016758	-0.009576	9.846699	0.046098	0.088199	-0.038104
+14.299980	-0.031123	-0.009576	9.868245	0.046231	0.086334	-0.034107
+14.301043	-0.004788	0.035911	9.810788	0.046364	0.086600	-0.031842
+14.301991	0.023940	0.002394	9.806000	0.046098	0.088732	-0.034107
+14.302986	0.076609	-0.031123	9.746149	0.047430	0.091130	-0.037172
+14.303969	0.043093	-0.004788	9.827546	0.044632	0.089398	-0.037571
+14.304960	0.052669	0.023940	9.827546	0.044632	0.087666	-0.038770
+14.306051	0.052669	0.016758	9.762907	0.043433	0.087000	-0.034507
+14.306969	0.050275	0.021546	9.746149	0.045565	0.088998	-0.033441
+14.307980	0.026334	0.040699	9.746149	0.047697	0.089531	-0.035706
+14.308980	0.057457	0.016758	9.774877	0.049562	0.090331	-0.035306
+14.309970	0.038305	-0.004788	9.827546	0.048496	0.090198	-0.035573
+14.310970	0.033517	0.019152	9.791636	0.048230	0.088865	-0.038104
+14.311967	-0.023940	0.016758	9.779666	0.049429	0.089265	-0.037438
+14.312964	-0.040699	0.004788	9.817970	0.048763	0.088599	-0.035972
+14.313981	-0.038305	-0.047881	9.822758	0.047963	0.089665	-0.036639
+14.314970	-0.009576	-0.016758	9.829940	0.048896	0.086467	-0.033974
+14.316042	0.011970	-0.021546	9.865851	0.048496	0.089265	-0.034107
+14.316982	-0.019152	-0.026334	9.837123	0.046897	0.092196	-0.033841
+14.317969	-0.019152	0.000000	9.803606	0.044499	0.090864	-0.037838
+14.318969	-0.031123	-0.067033	9.782060	0.046231	0.085268	-0.038770
+14.319961	-0.047881	-0.062245	9.789242	0.048363	0.082337	-0.034240
+14.320969	0.000000	-0.026334	9.810788	0.048629	0.086867	-0.034374
+14.321994	-0.014364	-0.026334	9.738967	0.047297	0.090064	-0.035839
+14.322939	0.019152	-0.009576	9.806000	0.045032	0.088599	-0.038237
+14.323964	-0.002394	0.019152	9.772483	0.046897	0.088066	-0.039170
+14.324967	0.019152	0.014364	9.772483	0.046764	0.087400	-0.036505
+14.325958	-0.011970	0.007182	9.743755	0.047430	0.088599	-0.033708
+14.326966	-0.019152	-0.062245	9.853881	0.046231	0.088066	-0.033308
+14.327962	-0.009576	-0.002394	9.839517	0.047031	0.089531	-0.034773
+14.328963	0.002394	0.031123	9.820364	0.046098	0.087266	-0.035040
+14.329955	-0.011970	0.009576	9.825152	0.046231	0.084602	-0.034507
+14.330944	-0.007182	0.023940	9.806000	0.047031	0.085668	-0.037571
+14.331952	0.045487	-0.002394	9.770089	0.047830	0.086600	-0.039037
+14.333013	0.009576	-0.002394	9.774877	0.046098	0.088466	-0.036372
+14.333986	-0.016758	0.002394	9.772483	0.044766	0.086067	-0.034507
+14.334976	-0.016758	0.019152	9.750937	0.045432	0.086334	-0.034374
+14.335970	-0.031123	-0.026334	9.832334	0.046764	0.086201	-0.034773
+14.336967	-0.045487	0.016758	9.885003	0.046631	0.087133	-0.036639
+14.337975	-0.069427	0.038305	9.911338	0.047031	0.087533	-0.036106
+14.338995	-0.021546	0.016758	9.892186	0.045698	0.087133	-0.035040
+14.340044	0.033517	0.011970	9.841911	0.046098	0.087933	-0.037305
+14.341014	0.028729	0.019152	9.839517	0.048096	0.091130	-0.035573
+14.341982	0.009576	0.079003	9.873033	0.047697	0.090864	-0.033708
+14.343021	0.069427	0.071821	9.892186	0.046764	0.088865	-0.035972
+14.344019	0.019152	-0.011970	9.839517	0.046098	0.088599	-0.036372
+14.344989	-0.019152	-0.045487	9.743755	0.045165	0.090464	-0.037172
+14.346019	0.000000	-0.026334	9.729391	0.045432	0.090730	-0.039836
+14.346989	-0.004788	-0.026334	9.779666	0.045165	0.088732	-0.035173
+14.347962	0.014364	0.007182	9.839517	0.046897	0.088199	-0.032775
+14.349019	0.009576	0.026334	9.803606	0.046764	0.087000	-0.033574
+14.349947	0.026334	0.028729	9.894580	0.047164	0.086867	-0.032908
+14.351020	0.019152	0.007182	9.837123	0.047297	0.085934	-0.035440
+14.351978	0.000000	-0.071821	9.822758	0.047830	0.085934	-0.036905
+14.352956	0.026334	0.011970	9.880215	0.050761	0.086467	-0.036772
+14.353954	-0.035911	-0.023940	9.798818	0.050628	0.088199	-0.037571
+14.354929	-0.004788	-0.040699	9.875427	0.047830	0.086867	-0.035573
+14.355930	0.026334	-0.009576	9.772483	0.047830	0.086067	-0.036505
+14.356925	0.014364	0.002394	9.858669	0.047963	0.085668	-0.037704
+14.357937	0.026334	-0.040699	9.868245	0.047697	0.084335	-0.036905
+14.358971	0.000000	0.014364	9.794030	0.046098	0.083936	-0.037038
+14.359973	0.004788	0.023940	9.796424	0.048363	0.088199	-0.033441
+14.360969	-0.033517	-0.026334	9.856275	0.048629	0.089798	-0.034773
+14.362021	-0.021546	-0.016758	9.853881	0.048096	0.087133	-0.035706
+14.363020	-0.011970	0.023940	9.829940	0.047697	0.088199	-0.035440
+14.364020	-0.014364	-0.023940	9.877821	0.045965	0.090331	-0.036905
+14.364983	0.023940	0.004788	9.817970	0.045032	0.088332	-0.035040
+14.366022	0.023940	0.031123	9.698268	0.048230	0.088998	-0.034107
+14.366986	0.000000	0.019152	9.705450	0.048230	0.088199	-0.037038
+14.367934	0.007182	0.023940	9.703056	0.049296	0.087400	-0.036106
+14.369014	0.031123	0.021546	9.827546	0.049828	0.089265	-0.035440
+14.370023	0.009576	-0.002394	9.853881	0.046764	0.090730	-0.039436
+14.371020	0.028729	-0.045487	9.798818	0.045965	0.087000	-0.042101
+14.372019	0.038305	0.033517	9.762907	0.047297	0.087400	-0.038637
+14.373019	-0.028729	0.031123	9.789242	0.048363	0.089531	-0.034507
+14.374020	-0.023940	-0.071821	9.858669	0.049029	0.085801	-0.037838
+14.375022	-0.007182	-0.026334	9.779666	0.047963	0.087266	-0.039836
+14.376021	0.035911	0.021546	9.782060	0.046364	0.087400	-0.038637
+14.377014	0.069427	0.047881	9.782060	0.047564	0.086867	-0.035440
+14.377985	0.035911	0.011970	9.748543	0.045565	0.085801	-0.032642
+14.379020	0.050275	-0.009576	9.767695	0.045432	0.084868	-0.035040
+14.380013	0.009576	-0.023940	9.837123	0.046897	0.087266	-0.035440
+14.381020	-0.009576	0.016758	9.794030	0.047031	0.091397	-0.037438
+14.382022	0.016758	-0.009576	9.734179	0.046231	0.090464	-0.037038
+14.383018	-0.021546	-0.023940	9.839517	0.045165	0.089398	-0.035839
+14.384013	-0.047881	0.000000	9.803606	0.045965	0.087533	-0.037305
+14.384944	0.040699	-0.019152	9.853881	0.049828	0.087799	-0.036239
+14.385956	0.004788	-0.019152	9.868245	0.050894	0.088199	-0.036372
+14.386961	0.014364	-0.062245	9.746149	0.050894	0.087133	-0.037038
+14.387952	-0.050275	-0.043093	9.772483	0.047164	0.089398	-0.036905
+14.389021	-0.007182	-0.009576	9.784454	0.044499	0.091263	-0.037305
+14.389983	0.043093	0.000000	9.794030	0.047031	0.090198	-0.036106
+14.390968	-0.016758	-0.026334	9.825152	0.049296	0.088998	-0.032775
+14.391997	-0.019152	-0.011970	9.865851	0.047697	0.087799	-0.035440
+14.392968	0.067033	0.026334	9.767695	0.046631	0.088066	-0.039170
+14.394020	0.059851	0.014364	9.738967	0.046098	0.088998	-0.038637
+14.395017	-0.031123	0.021546	9.796424	0.045832	0.088332	-0.036639
+14.395983	0.016758	0.011970	9.741361	0.047031	0.084202	-0.034640
+14.397007	0.033517	-0.016758	9.808394	0.050894	0.085135	-0.032642
+14.397953	0.004788	-0.021546	9.777271	0.050228	0.089398	-0.030510
+14.398967	0.021546	0.009576	9.827546	0.046631	0.091130	-0.030377
+14.399960	0.057457	0.055063	9.794030	0.045965	0.090597	-0.034640
+14.400960	0.031123	0.019152	9.808394	0.046364	0.089931	-0.039703
+14.401972	-0.023940	-0.004788	9.803606	0.045565	0.089132	-0.041168
+14.402969	-0.047881	0.021546	9.794030	0.047963	0.088865	-0.039703
+14.403972	-0.038305	-0.040699	9.806000	0.047963	0.086734	-0.036505
+14.404969	0.009576	0.019152	9.827546	0.045299	0.086734	-0.035040
+14.405969	-0.026334	0.026334	9.846699	0.044766	0.088466	-0.036505
+14.407018	-0.023940	0.004788	9.832334	0.046364	0.087400	-0.036772
+14.408019	0.007182	0.031123	9.827546	0.047164	0.087133	-0.033308
+14.409020	0.052669	-0.021546	9.964007	0.047963	0.087133	-0.035173
+14.409961	-0.016758	0.002394	9.887397	0.047430	0.089931	-0.037038
+14.410952	-0.033517	0.064639	9.815576	0.048096	0.091530	-0.035573
+14.411954	0.016758	0.014364	9.770089	0.047963	0.089665	-0.036505
+14.412967	0.045487	-0.028729	9.810788	0.048363	0.087533	-0.036772
+14.413964	0.014364	-0.009576	9.789242	0.048763	0.088066	-0.035972
+14.414940	0.033517	0.028729	9.765301	0.049562	0.088066	-0.035173
+14.415963	0.019152	0.011970	9.791636	0.047697	0.088199	-0.036106
+14.416967	-0.016758	0.000000	9.822758	0.047564	0.086334	-0.038237
+14.417975	-0.011970	-0.009576	9.779666	0.048496	0.084735	-0.038637
+14.418969	0.004788	0.033517	9.794030	0.049562	0.086067	-0.036772
+14.420019	0.014364	-0.009576	9.810788	0.050628	0.087933	-0.037704
+14.421018	-0.014364	0.047881	9.801212	0.050228	0.089531	-0.037971
+14.422020	-0.019152	0.014364	9.758119	0.049296	0.091530	-0.036639
+14.423012	-0.014364	0.009576	9.736573	0.045565	0.091263	-0.037438
+14.423978	0.007182	-0.045487	9.810788	0.043034	0.089798	-0.039037
+14.425014	0.009576	-0.019152	9.798818	0.045832	0.089132	-0.039037
+14.426021	-0.009576	-0.016758	9.861063	0.050495	0.090730	-0.036905
+14.427017	0.055063	-0.028729	9.853881	0.049828	0.091796	-0.036639
+14.428013	0.043093	-0.050275	9.839517	0.047430	0.088599	-0.034640
+14.429017	0.055063	-0.057457	9.839517	0.047963	0.086867	-0.033574
+14.429979	0.009576	0.004788	9.791636	0.046231	0.085002	-0.035173
+14.431019	-0.004788	-0.028729	9.827546	0.044366	0.085534	-0.037971
+14.432020	-0.038305	0.016758	9.841911	0.043300	0.087799	-0.033974
+14.433014	-0.007182	-0.040699	9.786848	0.045299	0.089665	-0.030776
+14.434011	0.000000	-0.035911	9.803606	0.048629	0.089531	-0.031443
+14.435013	0.026334	-0.031123	9.858669	0.047830	0.086201	-0.034907
+14.436019	0.016758	-0.021546	9.832334	0.047564	0.086067	-0.039303
+14.437019	-0.004788	-0.052669	9.798818	0.044233	0.087799	-0.038237
+14.438021	-0.026334	0.014364	9.777271	0.044766	0.088732	-0.036639
+14.439019	-0.043093	-0.016758	9.746149	0.045698	0.086067	-0.035573
+14.440020	-0.031123	0.028729	9.760513	0.046098	0.086600	-0.037305
+14.441013	-0.033517	0.067033	9.786848	0.044100	0.089398	-0.035839
+14.442020	0.021546	0.011970	9.837123	0.045565	0.090997	-0.037038
+14.443017	0.076609	-0.028729	9.892186	0.047564	0.089265	-0.036639
+14.443995	0.026334	0.019152	9.829940	0.047830	0.088199	-0.037172
+14.444977	0.016758	0.064639	9.853881	0.048363	0.088466	-0.036639
+14.446019	0.021546	0.014364	9.796424	0.047830	0.087799	-0.037305
+14.446979	0.026334	0.031123	9.748543	0.046631	0.088599	-0.034640
+14.448020	0.019152	-0.004788	9.822758	0.045565	0.090597	-0.035972
+14.449019	-0.011970	-0.011970	9.880215	0.046098	0.090198	-0.036905
+14.449951	-0.038305	-0.009576	9.801212	0.049029	0.085801	-0.036505
+14.450968	-0.023940	-0.007182	9.767695	0.048763	0.083936	-0.037038
+14.451968	-0.052669	0.035911	9.791636	0.047830	0.087400	-0.036905
+14.452969	-0.047881	0.023940	9.784454	0.046764	0.090331	-0.034374
+14.453962	-0.021546	0.009576	9.858669	0.045832	0.090730	-0.036106
+14.454989	-0.028729	0.000000	9.858669	0.046364	0.091130	-0.038770
+14.455972	-0.033517	0.040699	9.861063	0.047963	0.089798	-0.040902
+14.457018	-0.031123	-0.011970	9.808394	0.050894	0.087799	-0.036639
+14.457979	-0.016758	-0.033517	9.789242	0.050628	0.084202	-0.035306
+14.459026	0.000000	-0.043093	9.846699	0.047830	0.084735	-0.034773
+14.460018	-0.038305	-0.033517	9.844305	0.044632	0.087400	-0.036905
+14.461019	0.019152	-0.014364	9.873033	0.045565	0.088998	-0.040236
+14.462020	0.064639	-0.021546	9.817970	0.048496	0.090331	-0.039303
+14.463016	0.028729	-0.038305	9.789242	0.049429	0.092995	-0.035573
+14.464017	0.004788	-0.009576	9.772483	0.049562	0.090597	-0.036772
+14.465018	0.019152	0.031123	9.700662	0.048230	0.087933	-0.037172
+14.466021	-0.033517	0.026334	9.846699	0.046764	0.087133	-0.037172
+14.466990	0.019152	0.007182	9.952037	0.044233	0.088066	-0.036372
+14.468015	-0.009576	-0.040699	9.868245	0.045299	0.087799	-0.036505
+14.469021	0.019152	-0.002394	9.863457	0.047830	0.088199	-0.035306
+14.469976	0.055063	0.002394	9.868245	0.045698	0.087400	-0.036372
+14.471019	-0.002394	0.004788	9.861063	0.044899	0.087799	-0.038504
+14.472017	0.002394	0.026334	9.750937	0.046498	0.086467	-0.036106
+14.473019	-0.071821	0.002394	9.801212	0.046098	0.086734	-0.032642
+14.474020	-0.007182	0.002394	9.877821	0.046098	0.086334	-0.034107
+14.475017	-0.002394	0.019152	9.837123	0.047697	0.086600	-0.034374
+14.476023	0.011970	-0.038305	9.789242	0.049162	0.088732	-0.032508
+14.476970	0.019152	-0.011970	9.841911	0.048629	0.088066	-0.037172
+14.477975	-0.009576	-0.019152	9.822758	0.046364	0.088732	-0.035173
+14.479019	-0.007182	0.026334	9.772483	0.045432	0.085934	-0.034773
+14.479952	-0.028729	0.002394	9.765301	0.047031	0.086734	-0.036505
+14.481018	-0.009576	-0.045487	9.736573	0.048496	0.089798	-0.035706
+14.481980	-0.016758	0.023940	9.703056	0.049162	0.090597	-0.035306
+14.483019	-0.014364	0.002394	9.777271	0.047297	0.089931	-0.035040
+14.484017	0.021546	0.031123	9.753331	0.047164	0.087533	-0.035706
+14.485016	-0.033517	0.007182	9.772483	0.045698	0.086600	-0.034640
+14.486017	-0.038305	-0.031123	9.873033	0.048496	0.086600	-0.034640
+14.487006	0.009576	-0.016758	9.791636	0.050495	0.088199	-0.036106
+14.487982	0.098156	-0.035911	9.858669	0.049429	0.089132	-0.036905
+14.488966	0.031123	-0.028729	9.782060	0.044632	0.087400	-0.035173
+14.490017	0.002394	-0.021546	9.758119	0.043833	0.088466	-0.035040
+14.490957	0.009576	-0.004788	9.789242	0.047297	0.086467	-0.039969
+14.492019	0.031123	0.023940	9.822758	0.047164	0.086067	-0.037438
+14.493013	0.002394	0.019152	9.880215	0.045299	0.088466	-0.033308
+14.493975	-0.040699	0.035911	9.779666	0.043567	0.087666	-0.034374
+14.494967	0.028729	0.057457	9.827546	0.046231	0.086067	-0.036239
+14.495968	0.021546	0.004788	9.801212	0.046098	0.088599	-0.038770
+14.497019	-0.023940	0.002394	9.765301	0.045832	0.090464	-0.038637
+14.498007	-0.019152	0.021546	9.820364	0.046098	0.091530	-0.035173
+14.498976	0.026334	-0.009576	9.832334	0.046364	0.091263	-0.035173
+14.500017	0.035911	-0.014364	9.858669	0.046498	0.087266	-0.036772
+14.500953	0.047881	0.019152	9.798818	0.048230	0.086201	-0.034507
+14.501971	0.011970	0.043093	9.916126	0.048363	0.087400	-0.040769
+14.502967	0.040699	-0.009576	9.880215	0.047830	0.088599	-0.041035
+14.503959	0.038305	-0.019152	9.829940	0.049029	0.088865	-0.033841
+14.504958	0.021546	0.035911	9.777271	0.048763	0.089531	-0.032642
+14.505981	-0.035911	0.028729	9.832334	0.047697	0.088066	-0.035173
+14.507016	0.004788	-0.031123	9.834729	0.046231	0.087000	-0.034907
+14.508016	0.011970	-0.040699	9.777271	0.048096	0.087133	-0.040502
+14.509001	0.062245	-0.055063	9.760513	0.049562	0.087933	-0.035839
+14.509980	0.045487	-0.011970	9.806000	0.048496	0.088466	-0.034907
+14.511016	-0.014364	-0.040699	9.779666	0.047164	0.087400	-0.036905
+14.512019	-0.021546	-0.014364	9.717420	0.046231	0.085268	-0.035706
+14.513019	-0.031123	0.007182	9.774877	0.045965	0.086734	-0.032508
+14.514021	-0.016758	-0.009576	9.829940	0.045965	0.088066	-0.034107
+14.515001	0.009576	0.047881	9.801212	0.048363	0.087933	-0.036639
+14.516018	-0.007182	0.043093	9.796424	0.050361	0.088865	-0.037571
+14.517017	-0.007182	-0.033517	9.774877	0.050761	0.088599	-0.038504
+14.517949	0.040699	0.009576	9.813182	0.047963	0.085534	-0.036372
+14.518970	0.002394	-0.043093	9.825152	0.045965	0.087266	-0.036239
+14.519967	-0.014364	-0.002394	9.774877	0.046498	0.086734	-0.034640
+14.520972	0.043093	0.016758	9.753331	0.044766	0.086334	-0.036106
+14.521979	-0.021546	-0.021546	9.887397	0.045165	0.087666	-0.037571
+14.522970	0.031123	0.014364	9.810788	0.047164	0.088332	-0.038104
+14.524017	-0.011970	0.028729	9.849093	0.047697	0.088199	-0.037571
+14.525020	-0.007182	-0.026334	9.925702	0.047830	0.091397	-0.039170
+14.526019	-0.043093	-0.021546	9.834729	0.047031	0.089531	-0.035040
+14.527020	-0.019152	-0.033517	9.820364	0.048629	0.087133	-0.035040
+14.528019	-0.016758	0.021546	9.755725	0.049296	0.085668	-0.036505
+14.529020	-0.026334	0.028729	9.734179	0.049695	0.083536	-0.037438
+14.529965	-0.016758	0.000000	9.765301	0.047830	0.083536	-0.036106
+14.530962	0.035911	-0.028729	9.765301	0.046897	0.088599	-0.036505
+14.531973	0.011970	-0.009576	9.825152	0.045565	0.090198	-0.038770
+14.532970	-0.028729	-0.028729	9.865851	0.045032	0.089665	-0.038504
+14.533959	0.002394	-0.009576	9.750937	0.044499	0.088599	-0.034374
+14.534947	-0.009576	0.000000	9.703056	0.046231	0.087000	-0.033041
+14.535970	0.007182	-0.014364	9.789242	0.045565	0.087533	-0.035040
+14.536966	0.016758	0.019152	9.738967	0.050628	0.087266	-0.035173
+14.537944	0.052669	0.035911	9.796424	0.048363	0.090597	-0.032642
+14.539016	0.055063	-0.004788	9.865851	0.048096	0.091530	-0.038770
+14.540011	0.038305	-0.047881	9.839517	0.049029	0.091130	-0.041435
+14.541017	0.021546	-0.033517	9.741361	0.047430	0.088066	-0.040236
+14.541991	0.011970	-0.011970	9.724603	0.047963	0.086334	-0.036905
+14.543018	0.081397	-0.052669	9.691086	0.047430	0.085534	-0.033574
+14.544018	0.031123	-0.016758	9.760513	0.047697	0.088732	-0.033175
+14.545019	0.043093	-0.002394	9.791636	0.049296	0.090064	-0.035173
+14.545976	0.035911	0.014364	9.789242	0.047830	0.086734	-0.039303
+14.547016	0.038305	0.059851	9.844305	0.046364	0.085135	-0.037704
+14.548017	0.004788	0.028729	9.865851	0.047963	0.085135	-0.036639
+14.549018	0.014364	-0.004788	9.825152	0.049962	0.090064	-0.039436
+14.549988	-0.019152	-0.014364	9.712632	0.047963	0.091397	-0.035306
+14.550967	0.016758	0.016758	9.753331	0.046764	0.092196	-0.033175
+14.551966	0.002394	0.007182	9.743755	0.047031	0.089665	-0.032242
+14.553001	-0.055063	-0.007182	9.743755	0.046231	0.088332	-0.036772
+14.554019	0.002394	0.009576	9.741361	0.047697	0.086867	-0.038504
+14.555017	-0.057457	0.019152	9.698268	0.046897	0.084868	-0.038371
+14.556018	-0.038305	-0.038305	9.750937	0.047963	0.084735	-0.034773
+14.557018	0.016758	-0.076609	9.806000	0.049162	0.088865	-0.031709
+14.558020	0.038305	-0.007182	9.834729	0.049162	0.092063	-0.035306
+14.559018	0.050275	0.026334	9.837123	0.049296	0.089531	-0.036239
+14.559992	0.016758	0.069427	9.774877	0.048230	0.086867	-0.038371
+14.560974	-0.011970	0.009576	9.806000	0.045965	0.088466	-0.037838
+14.562004	0.016758	0.023940	9.885003	0.045698	0.089398	-0.036106
+14.563022	0.009576	0.059851	9.858669	0.046364	0.089531	-0.034507
+14.564006	-0.021546	0.038305	9.808394	0.045965	0.088599	-0.033841
+14.565018	0.033517	0.055063	9.772483	0.043700	0.086734	-0.039570
+14.566020	0.067033	0.011970	9.868245	0.042368	0.086600	-0.038904
+14.567018	0.050275	0.038305	9.849093	0.044233	0.088599	-0.034107
+14.568005	0.021546	0.064639	9.676722	0.044632	0.086201	-0.033974
+14.568969	-0.023940	0.023940	9.789242	0.045965	0.088066	-0.035306
+14.570021	0.040699	-0.016758	9.817970	0.046364	0.089665	-0.036106
+14.571013	0.011970	-0.014364	9.736573	0.047031	0.090331	-0.039436
+14.572008	-0.021546	0.004788	9.846699	0.047031	0.090597	-0.037838
+14.573015	-0.031123	-0.040699	9.877821	0.046498	0.086201	-0.035306
+14.574020	-0.035911	-0.019152	9.837123	0.045698	0.086734	-0.038104
+14.575019	-0.014364	0.009576	9.758119	0.047031	0.089798	-0.042634
+14.576017	-0.031123	0.004788	9.808394	0.046631	0.089265	-0.037971
+14.577019	0.026334	-0.002394	9.767695	0.048896	0.087000	-0.032642
+14.578019	0.011970	-0.023940	9.863457	0.048896	0.088066	-0.033574
+14.579019	0.002394	-0.014364	9.870639	0.046764	0.087400	-0.034773
+14.580014	-0.002394	0.033517	9.774877	0.045032	0.087000	-0.037172
+14.580972	0.011970	0.000000	9.741361	0.045565	0.088998	-0.037305
+14.581932	0.016758	-0.011970	9.806000	0.045832	0.089265	-0.037838
+14.582916	-0.021546	-0.004788	9.803606	0.045032	0.089398	-0.037571
+14.584013	-0.031123	-0.052669	9.832334	0.045698	0.087000	-0.035573
+14.585018	0.004788	-0.035911	9.746149	0.047697	0.085801	-0.034640
+14.586020	-0.004788	-0.031123	9.762907	0.048096	0.088732	-0.034374
+14.587017	0.028729	-0.043093	9.817970	0.046098	0.088865	-0.037438
+14.588018	0.007182	-0.011970	9.782060	0.047963	0.089931	-0.040502
+14.589003	-0.004788	-0.007182	9.817970	0.049429	0.090198	-0.038904
+14.589938	0.016758	-0.011970	9.801212	0.047297	0.088732	-0.037305
+14.590968	-0.031123	0.026334	9.863457	0.044499	0.087933	-0.038770
+14.591967	0.004788	0.014364	9.853881	0.045832	0.087133	-0.035040
+14.592965	0.007182	-0.011970	9.810788	0.046498	0.087799	-0.031443
+14.594007	-0.052669	-0.002394	9.786848	0.048096	0.089531	-0.030243
+14.595036	-0.040699	0.033517	9.815576	0.047430	0.089798	-0.033441
+14.596017	0.026334	-0.009576	9.877821	0.048230	0.089265	-0.034773
+14.596961	0.050275	-0.062245	9.832334	0.047697	0.086334	-0.035040
+14.597978	-0.071821	0.000000	9.849093	0.043833	0.083669	-0.039436
+14.599012	-0.021546	0.016758	9.796424	0.042234	0.086734	-0.039436
+14.600018	0.067033	-0.028729	9.813182	0.043966	0.088332	-0.036106
+14.600992	-0.040699	0.021546	9.861063	0.046764	0.087400	-0.034773
+14.601973	-0.055063	-0.028729	9.882609	0.045832	0.086867	-0.036106
+14.602968	-0.016758	-0.016758	9.806000	0.046364	0.088865	-0.039303
+14.603927	0.035911	0.028729	9.806000	0.049828	0.089265	-0.037172
+14.604924	0.028729	0.002394	9.794030	0.049828	0.089265	-0.032642
+14.605927	0.019152	-0.019152	9.832334	0.048629	0.088998	-0.033308
+14.607009	-0.021546	-0.004788	9.794030	0.044766	0.087133	-0.035972
+14.608018	0.026334	-0.007182	9.798818	0.045432	0.088332	-0.036639
+14.609018	0.011970	0.000000	9.813182	0.047830	0.087933	-0.040502
+14.610019	0.009576	0.004788	9.779666	0.047697	0.088732	-0.038104
+14.611018	0.009576	-0.004788	9.817970	0.046231	0.090064	-0.034907
+14.612017	0.035911	0.000000	9.798818	0.044499	0.088998	-0.035706
+14.613017	0.035911	-0.021546	9.825152	0.043833	0.088599	-0.036239
+14.614020	-0.007182	-0.009576	9.794030	0.045965	0.090464	-0.035573
+14.615018	-0.019152	0.007182	9.784454	0.046098	0.090198	-0.034507
+14.616016	-0.007182	-0.016758	9.837123	0.046498	0.087666	-0.032109
+14.617006	0.000000	0.004788	9.887397	0.047697	0.089132	-0.035839
+14.618016	0.021546	-0.057457	9.789242	0.046897	0.088998	-0.039969
+14.618941	0.040699	0.016758	9.746149	0.048363	0.087533	-0.038504
+14.619975	0.009576	0.052669	9.779666	0.045432	0.085801	-0.035573
+14.621017	0.035911	0.023940	9.738967	0.048763	0.085268	-0.034374
+14.621978	0.014364	0.031123	9.784454	0.048763	0.087666	-0.037704
+14.622967	0.028729	0.009576	9.834729	0.045299	0.085135	-0.042101
+14.623966	-0.016758	-0.007182	9.806000	0.045565	0.083270	-0.039303
+14.624964	-0.031123	-0.023940	9.849093	0.048896	0.084069	-0.034773
+14.625971	0.014364	-0.033517	9.841911	0.049296	0.085135	-0.034107
+14.626968	0.071821	0.002394	9.731785	0.048896	0.086600	-0.035173
+14.627971	0.021546	0.019152	9.770089	0.048496	0.088732	-0.036905
+14.628962	0.019152	0.007182	9.853881	0.046231	0.089398	-0.037971
+14.629937	0.035911	-0.014364	9.870639	0.048763	0.091530	-0.036372
+14.630968	-0.021546	0.038305	9.861063	0.048496	0.090198	-0.034640
+14.632017	-0.016758	0.009576	9.832334	0.048096	0.088199	-0.038371
+14.633020	-0.007182	0.023940	9.782060	0.048629	0.088332	-0.043034
+14.634019	0.011970	0.050275	9.808394	0.048896	0.087799	-0.039436
+14.634938	0.021546	0.057457	9.832334	0.046231	0.089132	-0.035573
+14.636011	0.035911	0.019152	9.844305	0.044766	0.087666	-0.034374
+14.637015	0.019152	0.038305	9.829940	0.046897	0.086334	-0.036239
+14.638017	-0.004788	-0.007182	9.875427	0.045432	0.083270	-0.036639
+14.638963	-0.007182	-0.038305	9.806000	0.044499	0.086067	-0.037838
+14.639977	-0.011970	-0.043093	9.743755	0.042501	0.088998	-0.038637
+14.641020	0.011970	-0.026334	9.729391	0.046631	0.087799	-0.036639
+14.642017	-0.004788	-0.083792	9.789242	0.047297	0.088332	-0.033974
+14.643017	0.000000	-0.031123	9.777271	0.047031	0.084868	-0.034107
+14.644017	0.023940	0.047881	9.786848	0.046897	0.085668	-0.033708
+14.645014	0.014364	0.019152	9.844305	0.045432	0.087133	-0.031576
+14.646018	0.009576	0.031123	9.839517	0.046498	0.086734	-0.036106
+14.647017	-0.028729	-0.004788	9.853881	0.046897	0.088066	-0.038637
+14.648018	0.043093	-0.019152	9.791636	0.045299	0.090730	-0.040902
+14.648977	0.033517	-0.074215	9.758119	0.045565	0.090198	-0.037172
+14.650015	0.028729	-0.047881	9.851487	0.047430	0.088332	-0.035173
+14.650942	0.052669	0.002394	9.765301	0.044766	0.084335	-0.039037
+14.651926	0.035911	-0.019152	9.762907	0.045698	0.085401	-0.035440
+14.653018	0.052669	-0.050275	9.839517	0.047830	0.087666	-0.036639
+14.654013	0.021546	0.009576	9.875427	0.048230	0.088998	-0.038104
+14.655020	-0.014364	-0.011970	9.849093	0.049429	0.090464	-0.037172
+14.656014	-0.009576	-0.014364	9.832334	0.047164	0.088998	-0.035839
+14.657018	-0.028729	0.026334	9.839517	0.044632	0.086467	-0.037172
+14.658019	-0.009576	-0.014364	9.789242	0.044766	0.084202	-0.039703
+14.659000	0.031123	-0.050275	9.839517	0.045965	0.085135	-0.039969
+14.659975	0.035911	-0.038305	9.803606	0.047164	0.087000	-0.034640
+14.660969	-0.033517	-0.014364	9.822758	0.046364	0.087933	-0.036505
+14.661972	-0.026334	-0.026334	9.808394	0.046897	0.086867	-0.040636
+14.663013	-0.004788	-0.035911	9.803606	0.047164	0.085934	-0.037971
+14.663971	0.043093	-0.045487	9.772483	0.046897	0.085401	-0.035972
+14.664944	0.031123	-0.038305	9.767695	0.047031	0.086600	-0.041302
+14.665980	-0.002394	-0.028729	9.834729	0.046498	0.090331	-0.037971
+14.666966	0.035911	-0.043093	9.815576	0.047297	0.091930	-0.035706
+14.667957	0.004788	-0.019152	9.849093	0.045032	0.086734	-0.034907
+14.668967	-0.011970	-0.021546	9.928096	0.046364	0.085002	-0.034907
+14.669962	-0.031123	0.021546	9.892186	0.045832	0.088732	-0.035440
+14.670968	-0.002394	-0.021546	9.760513	0.046098	0.090064	-0.041435
+14.671982	-0.019152	0.014364	9.806000	0.046231	0.091130	-0.040636
+14.673014	-0.019152	0.009576	9.827546	0.045299	0.090597	-0.034773
+14.674019	0.040699	0.000000	9.880215	0.047963	0.087533	-0.033841
+14.675015	0.021546	0.014364	9.875427	0.047164	0.085401	-0.035040
+14.676015	-0.045487	-0.031123	9.798818	0.048496	0.084602	-0.035839
+14.677014	-0.028729	-0.067033	9.748543	0.047430	0.084335	-0.040902
+14.678018	0.043093	-0.038305	9.789242	0.049962	0.087933	-0.040103
+14.679003	0.000000	-0.062245	9.786848	0.049296	0.089665	-0.038904
+14.680014	-0.019152	-0.035911	9.777271	0.047963	0.091796	-0.037704
+14.680992	0.033517	-0.026334	9.794030	0.044766	0.092596	-0.036239
+14.682005	0.045487	-0.031123	9.777271	0.044632	0.089265	-0.035306
+14.683009	0.031123	0.007182	9.844305	0.047830	0.084735	-0.037305
+14.684018	0.004788	-0.059851	9.806000	0.048496	0.085934	-0.037172
+14.685015	-0.028729	-0.088580	9.851487	0.048496	0.088599	-0.036239
+14.685961	0.045487	-0.043093	9.829940	0.049162	0.090331	-0.034240
+14.686926	0.009576	0.021546	9.851487	0.048496	0.087266	-0.031842
+14.687918	0.035911	0.035911	9.841911	0.044632	0.088732	-0.034640
+14.689012	0.016758	-0.011970	9.875427	0.043300	0.089798	-0.035839
+14.690019	-0.038305	-0.019152	9.892186	0.045965	0.089398	-0.036239
+14.690944	-0.007182	-0.004788	9.844305	0.047031	0.091130	-0.035040
+14.691980	0.002394	0.031123	9.803606	0.045165	0.089531	-0.034107
+14.692975	-0.023940	0.000000	9.815576	0.046498	0.086600	-0.037172
+14.694016	-0.023940	0.000000	9.815576	0.047164	0.085934	-0.039570
+14.695014	0.028729	-0.016758	9.861063	0.047697	0.087400	-0.035573
+14.696010	0.023940	-0.059851	9.882609	0.049029	0.088332	-0.036639
+14.697017	-0.002394	-0.088580	9.808394	0.047297	0.085268	-0.037305
+14.698017	0.011970	-0.019152	9.822758	0.047297	0.085801	-0.037172
+14.699013	-0.019152	-0.011970	9.827546	0.046364	0.088066	-0.034773
+14.699926	0.004788	0.035911	9.829940	0.044499	0.088466	-0.036639
+14.700916	0.045487	0.011970	9.837123	0.046098	0.088466	-0.037172
+14.701971	0.057457	-0.040699	9.770089	0.045965	0.087799	-0.034374
+14.702959	0.004788	-0.031123	9.767695	0.046364	0.085668	-0.035972
+14.704036	-0.033517	0.002394	9.810788	0.046631	0.085534	-0.038104
+14.704967	0.047881	-0.019152	9.808394	0.045832	0.086201	-0.037704
+14.706012	0.004788	-0.009576	9.899368	0.044899	0.090730	-0.037838
+14.707013	0.088580	-0.052669	9.760513	0.046498	0.089931	-0.038104
+14.708014	0.031123	-0.002394	9.803606	0.046897	0.089398	-0.041168
+14.708948	-0.004788	-0.019152	9.844305	0.046498	0.090864	-0.041968
+14.710016	-0.021546	-0.021546	9.853881	0.049828	0.092729	-0.038237
+14.711015	-0.021546	-0.009576	9.839517	0.050495	0.089931	-0.034907
+14.712014	-0.028729	-0.035911	9.801212	0.047697	0.086734	-0.035173
+14.712967	0.026334	-0.052669	9.853881	0.046764	0.086334	-0.038904
+14.714039	0.019152	0.011970	9.882609	0.047430	0.084469	-0.037971
+14.715013	-0.016758	0.016758	9.837123	0.047430	0.084868	-0.034640
+14.716013	-0.055063	-0.016758	9.791636	0.047697	0.085534	-0.036106
+14.717018	0.004788	0.019152	9.822758	0.047430	0.086467	-0.035706
+14.718019	0.014364	-0.019152	9.858669	0.047164	0.087666	-0.032508
+14.719016	0.028729	-0.028729	9.815576	0.046631	0.089398	-0.034640
+14.720014	-0.026334	-0.026334	9.825152	0.045698	0.089931	-0.034773
+14.721013	-0.016758	0.014364	9.743755	0.045165	0.087933	-0.035839
+14.722017	0.062245	0.064639	9.698268	0.046231	0.086600	-0.037571
+14.723001	0.033517	0.002394	9.784454	0.047031	0.089531	-0.037038
+14.724003	0.026334	-0.047881	9.827546	0.047564	0.089265	-0.035839
+14.724955	0.000000	-0.002394	9.827546	0.046364	0.088332	-0.034107
+14.725955	0.000000	-0.016758	9.801212	0.047297	0.085401	-0.035972
+14.726933	0.004788	0.026334	9.758119	0.048096	0.086201	-0.039037
+14.727937	0.016758	0.038305	9.817970	0.046764	0.087000	-0.037704
+14.728939	0.031123	-0.035911	9.858669	0.048230	0.088732	-0.036372
+14.729934	0.069427	0.000000	9.786848	0.048496	0.088599	-0.034640
+14.730940	0.026334	-0.002394	9.832334	0.047830	0.087799	-0.035706
+14.731926	-0.019152	-0.014364	9.849093	0.046764	0.088332	-0.038371
+14.732935	0.000000	0.043093	9.822758	0.047697	0.090198	-0.035573
+14.733937	-0.057457	0.007182	9.817970	0.048230	0.089265	-0.033041
+14.734972	-0.045487	-0.026334	9.762907	0.045565	0.089931	-0.036239
+14.735994	-0.007182	0.009576	9.772483	0.044499	0.089132	-0.038504
+14.736999	0.031123	0.035911	9.770089	0.045299	0.089798	-0.040236
+14.737956	0.019152	0.014364	9.794030	0.044233	0.091263	-0.036372
+14.739013	-0.011970	-0.004788	9.676722	0.042368	0.091263	-0.035573
+14.739973	0.016758	-0.002394	9.729391	0.044766	0.088998	-0.037172
+14.741013	0.002394	0.059851	9.801212	0.048096	0.084868	-0.037038
+14.741936	0.045487	0.052669	9.777271	0.049562	0.086067	-0.035839
+14.742950	-0.014364	0.016758	9.798818	0.050495	0.088732	-0.039436
+14.743976	0.004788	0.014364	9.858669	0.048496	0.089132	-0.039703
+14.745016	-0.002394	-0.050275	9.784454	0.047164	0.088732	-0.036372
+14.746016	-0.021546	-0.043093	9.741361	0.045965	0.087666	-0.035440
+14.747015	0.033517	-0.040699	9.782060	0.047164	0.088066	-0.036106
+14.747997	0.028729	-0.023940	9.858669	0.045965	0.090064	-0.035839
+14.748999	-0.055063	-0.026334	9.786848	0.045432	0.090864	-0.034374
+14.749994	0.019152	-0.033517	9.755725	0.044766	0.087266	-0.031975
+14.750957	0.076609	0.002394	9.837123	0.044499	0.085401	-0.034507
+14.752013	-0.011970	0.000000	9.796424	0.046764	0.086201	-0.035573
+14.753009	-0.031123	0.004788	9.789242	0.046231	0.086867	-0.032775
+14.754017	0.011970	0.002394	9.750937	0.046631	0.088599	-0.034773
+14.755016	0.059851	0.019152	9.806000	0.047297	0.091796	-0.035972
+14.756017	0.043093	0.021546	9.841911	0.048363	0.093795	-0.038770
+14.757008	0.009576	0.019152	9.834729	0.049162	0.089931	-0.035040
+14.757990	-0.014364	-0.004788	9.870639	0.046764	0.086734	-0.032775
+14.758976	0.009576	-0.019152	9.868245	0.045832	0.087266	-0.034240
+14.759998	-0.045487	-0.040699	9.820364	0.044632	0.087266	-0.034240
+14.761009	0.016758	-0.023940	9.822758	0.046897	0.086201	-0.035573
+14.762015	0.059851	-0.026334	9.796424	0.048363	0.085002	-0.038504
+14.763013	0.007182	-0.021546	9.820364	0.047830	0.086600	-0.036106
+14.764012	0.002394	0.000000	9.803606	0.046897	0.088199	-0.034107
+14.765013	-0.026334	0.004788	9.765301	0.045032	0.089798	-0.034240
+14.766017	-0.067033	-0.016758	9.748543	0.047031	0.088332	-0.035839
+14.767012	0.002394	-0.016758	9.750937	0.048096	0.085668	-0.037838
+14.767997	-0.045487	0.014364	9.837123	0.049296	0.083003	-0.035306
+14.768981	-0.007182	-0.009576	9.794030	0.047297	0.085668	-0.032775
+14.770004	-0.019152	-0.004788	9.791636	0.046498	0.088466	-0.036639
+14.771009	-0.021546	-0.016758	9.796424	0.048096	0.089931	-0.035573
+14.772013	-0.033517	-0.040699	9.815576	0.047297	0.090464	-0.037172
+14.773016	-0.019152	0.007182	9.822758	0.046498	0.090064	-0.039170
+14.774016	0.011970	-0.028729	9.731785	0.045832	0.088332	-0.037704
+14.775003	-0.007182	-0.011970	9.786848	0.047697	0.089265	-0.035040
+14.776012	0.016758	0.050275	9.726997	0.048096	0.090464	-0.030510
+14.777013	-0.026334	0.014364	9.760513	0.046897	0.089665	-0.033574
+14.778014	0.038305	0.040699	9.729391	0.047697	0.087666	-0.040103
+14.778997	0.043093	-0.009576	9.789242	0.049162	0.086867	-0.036905
+14.779939	-0.026334	-0.016758	9.806000	0.050361	0.089265	-0.033308
+14.781008	0.021546	-0.002394	9.813182	0.047164	0.089531	-0.033974
+14.782015	0.035911	0.004788	9.849093	0.044233	0.087933	-0.035440
+14.783012	0.033517	0.021546	9.853881	0.044899	0.087666	-0.036772
+14.784015	0.019152	0.004788	9.784454	0.047830	0.086201	-0.036639
+14.784950	0.004788	-0.055063	9.767695	0.047697	0.086067	-0.035173
+14.786016	-0.014364	-0.028729	9.820364	0.046364	0.089531	-0.035173
+14.787007	-0.038305	-0.047881	9.822758	0.043433	0.092329	-0.035440
+14.788013	0.059851	-0.059851	9.784454	0.045832	0.091663	-0.033974
+14.788996	0.031123	-0.019152	9.806000	0.049562	0.087266	-0.037172
+14.789981	0.021546	0.000000	9.808394	0.049828	0.088332	-0.039037
+14.791008	0.011970	0.031123	9.758119	0.047830	0.086067	-0.038904
+14.792015	-0.002394	0.028729	9.806000	0.046231	0.085268	-0.036505
+14.793021	-0.019152	-0.033517	9.846699	0.046498	0.089132	-0.035972
+14.794016	0.050275	-0.007182	9.786848	0.044499	0.087533	-0.038104
+14.795012	0.059851	0.009576	9.731785	0.044632	0.086734	-0.036639
+14.796015	0.045487	-0.052669	9.784454	0.046897	0.086600	-0.037305
+14.797014	0.023940	-0.050275	9.822758	0.049029	0.085268	-0.038237
+14.798015	0.062245	0.011970	9.908944	0.051161	0.086201	-0.033708
+14.798994	0.045487	0.023940	9.837123	0.049695	0.087266	-0.030776
+14.800004	0.047881	-0.035911	9.808394	0.045432	0.088732	-0.031043
+14.800963	0.019152	-0.035911	9.750937	0.045965	0.087400	-0.035706
+14.802015	0.023940	0.031123	9.722208	0.046764	0.086467	-0.038104
+14.803012	0.004788	0.031123	9.765301	0.048363	0.085002	-0.039037
+14.804015	0.016758	0.021546	9.815576	0.047963	0.086600	-0.035440
+14.805008	-0.004788	0.050275	9.794030	0.045965	0.087133	-0.035040
+14.806016	0.004788	0.033517	9.782060	0.046364	0.087799	-0.038237
+14.807014	0.004788	-0.009576	9.724603	0.046098	0.088066	-0.037305
+14.807955	-0.038305	0.040699	9.758119	0.046364	0.087133	-0.036639
+14.808987	0.002394	-0.011970	9.817970	0.045432	0.086201	-0.036905
+14.809959	-0.028729	-0.004788	9.829940	0.047430	0.087266	-0.035173
+14.810950	0.043093	-0.011970	9.813182	0.048496	0.086734	-0.035706
+14.811957	0.021546	0.028729	9.789242	0.046498	0.087666	-0.038770
+14.813015	-0.016758	0.033517	9.779666	0.045565	0.088865	-0.038904
+14.814015	-0.004788	-0.055063	9.846699	0.044100	0.088332	-0.038770
+14.815013	0.000000	-0.062245	9.892186	0.046231	0.088599	-0.038904
+14.816012	0.038305	-0.019152	9.806000	0.047031	0.089132	-0.038904
+14.817008	0.028729	0.069427	9.760513	0.045698	0.086734	-0.039303
+14.818015	0.016758	-0.047881	9.803606	0.045565	0.084868	-0.039037
+14.818967	-0.023940	-0.038305	9.798818	0.046764	0.085934	-0.035839
+14.820012	-0.028729	-0.023940	9.786848	0.046231	0.088332	-0.036372
+14.820984	0.011970	-0.014364	9.798818	0.047564	0.087666	-0.035839
+14.821972	0.033517	0.023940	9.789242	0.049029	0.085401	-0.034107
+14.823014	0.009576	-0.023940	9.827546	0.046364	0.086201	-0.038504
+14.824012	0.019152	-0.009576	9.837123	0.046897	0.088732	-0.040236
+14.825015	0.059851	0.038305	9.794030	0.047430	0.089398	-0.041968
+14.826015	0.043093	0.014364	9.765301	0.046364	0.088466	-0.037438
+14.827010	0.035911	0.050275	9.801212	0.046897	0.088066	-0.035040
+14.828016	0.023940	-0.055063	9.746149	0.047564	0.088066	-0.034640
+14.829016	0.028729	-0.031123	9.758119	0.048763	0.087400	-0.037038
+14.829968	-0.021546	0.023940	9.765301	0.048496	0.088466	-0.036639
+14.831016	0.035911	0.009576	9.798818	0.047564	0.089665	-0.035306
+14.831968	0.021546	-0.009576	9.870639	0.048896	0.087533	-0.033841
+14.833006	0.067033	-0.040699	9.880215	0.048230	0.086734	-0.035173
+14.833949	0.083792	-0.040699	9.880215	0.049029	0.087533	-0.035440
+14.834921	0.071821	-0.007182	9.808394	0.047963	0.089798	-0.038104
+14.836011	0.016758	-0.035911	9.841911	0.045698	0.090730	-0.035972
+14.837013	0.050275	0.009576	9.815576	0.046364	0.089531	-0.035440
+14.838000	-0.033517	-0.026334	9.841911	0.047697	0.091930	-0.033708
+14.839033	0.000000	-0.009576	9.877821	0.048629	0.091930	-0.034907
+14.840010	0.019152	-0.028729	9.913732	0.049562	0.090464	-0.037704
+14.840972	0.009576	0.004788	9.808394	0.046897	0.088466	-0.037305
+14.841974	0.026334	-0.002394	9.770089	0.046498	0.086334	-0.035173
+14.842998	0.055063	0.000000	9.782060	0.047297	0.086334	-0.037172
+14.844012	0.028729	-0.045487	9.743755	0.047164	0.086600	-0.037305
+14.844953	0.038305	-0.035911	9.724603	0.046631	0.087133	-0.036505
+14.846016	0.019152	-0.038305	9.873033	0.047297	0.088599	-0.035440
+14.847012	0.009576	-0.019152	9.841911	0.047564	0.088599	-0.036905
+14.848008	0.028729	-0.004788	9.817970	0.044366	0.087666	-0.036239
+14.849012	0.014364	-0.019152	9.786848	0.045432	0.086067	-0.034107
+14.850015	-0.004788	-0.028729	9.726997	0.047697	0.087400	-0.036239
+14.850938	-0.019152	-0.026334	9.849093	0.045698	0.086067	-0.037838
+14.851986	0.052669	-0.059851	9.832334	0.044366	0.085135	-0.034374
+14.853004	0.031123	0.011970	9.760513	0.045565	0.086867	-0.033175
+14.854003	-0.007182	0.023940	9.734179	0.043833	0.085534	-0.035839
+14.854999	-0.007182	0.009576	9.801212	0.045165	0.086467	-0.035972
+14.856015	-0.019152	0.011970	9.849093	0.045565	0.088199	-0.036905
+14.857012	0.009576	-0.045487	9.863457	0.047297	0.087799	-0.039037
+14.858016	-0.007182	-0.040699	9.810788	0.047830	0.090331	-0.040236
+14.859011	0.004788	-0.057457	9.758119	0.048363	0.091397	-0.038371
+14.859995	0.035911	-0.026334	9.782060	0.047697	0.087799	-0.036905
+14.861013	0.019152	-0.050275	9.707844	0.048096	0.085534	-0.037838
+14.862024	0.026334	0.019152	9.779666	0.048230	0.085534	-0.035040
+14.862934	-0.011970	0.050275	9.846699	0.048496	0.087799	-0.033841
+14.863989	-0.019152	0.033517	9.767695	0.048230	0.085534	-0.034907
+14.865014	-0.052669	0.019152	9.767695	0.045965	0.085002	-0.037305
+14.866016	-0.009576	0.043093	9.820364	0.045832	0.088466	-0.039170
+14.867016	0.019152	0.028729	9.789242	0.047297	0.090064	-0.039703
+14.868012	0.021546	-0.019152	9.743755	0.049429	0.090064	-0.037571
+14.869016	-0.002394	-0.047881	9.738967	0.049296	0.089398	-0.036505
+14.870016	0.050275	-0.009576	9.719814	0.047830	0.086734	-0.037438
+14.871011	0.019152	0.004788	9.786848	0.046364	0.087933	-0.036106
+14.872015	0.016758	0.009576	9.755725	0.045165	0.088865	-0.035040
+14.872982	0.016758	0.004788	9.810788	0.045432	0.088599	-0.035573
+14.874014	0.038305	-0.031123	9.851487	0.048363	0.087666	-0.034907
+14.875002	0.026334	-0.040699	9.858669	0.050228	0.088998	-0.034773
+14.876013	0.028729	0.004788	9.913732	0.048896	0.088998	-0.033708
+14.877011	0.052669	0.009576	9.868245	0.048096	0.086067	-0.036505
+14.878016	0.004788	-0.031123	9.750937	0.045032	0.084602	-0.041435
+14.879008	0.011970	0.026334	9.777271	0.044366	0.087266	-0.038371
+14.880011	0.014364	-0.023940	9.722208	0.043700	0.088066	-0.035573
+14.881000	0.028729	-0.026334	9.698268	0.047564	0.087799	-0.035573
+14.882013	0.064639	0.023940	9.782060	0.049962	0.085801	-0.033708
+14.883011	0.000000	-0.009576	9.827546	0.048230	0.083936	-0.035972
+14.883955	-0.014364	-0.028729	9.844305	0.045698	0.086734	-0.037172
+14.884980	0.011970	-0.011970	9.834729	0.046764	0.088332	-0.034374
+14.886013	0.009576	-0.045487	9.770089	0.047031	0.089265	-0.035573
+14.887011	-0.031123	0.007182	9.801212	0.048096	0.087933	-0.033841
+14.888027	0.000000	-0.031123	9.772483	0.049029	0.087000	-0.034907
+14.889013	-0.014364	-0.016758	9.772483	0.049029	0.086867	-0.032242
+14.890014	0.004788	-0.047881	9.738967	0.047830	0.087533	-0.033175
+14.891007	0.014364	-0.038305	9.817970	0.046897	0.087933	-0.036106
+14.892009	-0.028729	-0.040699	9.817970	0.048629	0.088066	-0.036772
+14.893000	-0.011970	-0.093368	9.822758	0.048896	0.088466	-0.037571
+14.894004	-0.071821	-0.088580	9.837123	0.047031	0.090064	-0.036505
+14.895016	-0.047881	0.057457	9.770089	0.045832	0.088466	-0.036772
+14.896012	-0.033517	0.021546	9.765301	0.048230	0.088066	-0.035839
+14.896950	-0.004788	-0.002394	9.729391	0.048896	0.088332	-0.031709
+14.897964	0.019152	-0.014364	9.829940	0.045965	0.087266	-0.030510
+14.899007	0.009576	0.038305	9.817970	0.044233	0.087666	-0.031176
+14.899985	0.028729	-0.019152	9.770089	0.044899	0.087266	-0.033841
+14.901013	0.011970	-0.011970	9.770089	0.047430	0.086334	-0.033841
+14.901996	0.035911	0.009576	9.760513	0.048096	0.084469	-0.035440
+14.903011	0.059851	-0.043093	9.731785	0.047297	0.087000	-0.037438
+14.904013	0.000000	-0.031123	9.688692	0.046364	0.089132	-0.035839
+14.904987	0.050275	-0.028729	9.786848	0.045299	0.088732	-0.034640
+14.906011	0.055063	-0.026334	9.770089	0.046498	0.087933	-0.036372
+14.907014	0.028729	0.033517	9.738967	0.047564	0.086067	-0.035440
+14.908014	-0.004788	0.002394	9.736573	0.047697	0.089265	-0.034240
+14.909012	0.014364	0.011970	9.904156	0.045032	0.088199	-0.034240
+14.910013	0.028729	0.021546	9.810788	0.045832	0.088199	-0.037305
+14.911014	-0.009576	0.002394	9.806000	0.045165	0.088466	-0.037571
+14.912013	-0.069427	-0.019152	9.880215	0.044632	0.088732	-0.034507
+14.913012	-0.038305	-0.019152	9.784454	0.043833	0.087000	-0.033441
+14.914003	0.021546	0.026334	9.801212	0.044233	0.086734	-0.031576
+14.914968	0.028729	0.004788	9.839517	0.044899	0.086201	-0.035040
+14.915973	0.004788	-0.026334	9.827546	0.046231	0.087133	-0.035573
+14.916924	0.038305	-0.031123	9.853881	0.046764	0.087533	-0.034374
+14.917914	-0.016758	-0.019152	9.782060	0.046098	0.086334	-0.038104
+14.918920	0.000000	-0.004788	9.796424	0.047963	0.088998	-0.038637
+14.919947	0.016758	0.000000	9.750937	0.049296	0.088599	-0.035706
+14.920988	0.052669	-0.011970	9.849093	0.046631	0.087133	-0.036106
+14.922015	0.019152	0.007182	9.813182	0.047031	0.087133	-0.035706
+14.922988	0.002394	-0.031123	9.875427	0.045165	0.088066	-0.037172
+14.923961	-0.002394	-0.033517	9.839517	0.044766	0.090997	-0.037838
+14.925011	-0.019152	-0.021546	9.820364	0.043833	0.088066	-0.035706
+14.925995	-0.007182	-0.057457	9.858669	0.045032	0.085668	-0.035972
+14.926972	0.007182	-0.059851	9.870639	0.048230	0.084202	-0.038637
+14.928013	0.000000	-0.064639	9.798818	0.046231	0.084469	-0.037838
+14.929012	0.014364	0.019152	9.825152	0.044366	0.088199	-0.035040
+14.930000	0.035911	0.021546	9.820364	0.044899	0.089132	-0.034640
+14.931012	0.000000	-0.038305	9.755725	0.045565	0.089132	-0.037172
+14.932013	0.021546	-0.035911	9.748543	0.048629	0.086734	-0.038371
+14.933011	0.000000	-0.035911	9.796424	0.049695	0.086067	-0.036639
+14.934014	0.019152	0.016758	9.738967	0.048896	0.087266	-0.037038
+14.934950	0.009576	-0.016758	9.779666	0.048363	0.087133	-0.040236
+14.936011	-0.026334	-0.019152	9.738967	0.046631	0.089265	-0.039037
+14.936982	-0.016758	0.021546	9.779666	0.045965	0.090597	-0.037305
+14.938009	-0.002394	-0.009576	9.779666	0.047164	0.088732	-0.037971
+14.939011	0.000000	0.000000	9.827546	0.047963	0.087666	-0.039570
+14.940012	-0.062245	0.002394	9.829940	0.049429	0.089665	-0.040902
+14.940970	-0.038305	-0.019152	9.767695	0.048629	0.091530	-0.036106
+14.942015	-0.045487	0.021546	9.784454	0.049429	0.088466	-0.036106
+14.943006	-0.026334	0.031123	9.803606	0.047430	0.088199	-0.034107
+14.944011	-0.009576	-0.045487	9.798818	0.045432	0.086201	-0.038504
+14.945011	-0.028729	-0.052669	9.715026	0.045698	0.088199	-0.041835
+14.946001	0.043093	-0.021546	9.712632	0.048096	0.088466	-0.040236
+14.946998	0.021546	0.004788	9.770089	0.047963	0.086201	-0.036239
+14.948013	0.040699	0.002394	9.817970	0.044766	0.083136	-0.038371
+14.949012	0.064639	0.057457	9.734179	0.045565	0.083403	-0.040236
+14.949979	0.000000	0.021546	9.719814	0.047963	0.086201	-0.042368
+14.950950	0.002394	0.019152	9.782060	0.048896	0.085801	-0.039037
+14.951961	0.023940	0.069427	9.734179	0.047430	0.085801	-0.036772
+14.953011	-0.011970	-0.026334	9.796424	0.048230	0.086201	-0.037838
+14.954015	-0.011970	-0.014364	9.810788	0.048629	0.087666	-0.036372
+14.955010	-0.028729	-0.028729	9.801212	0.046098	0.088332	-0.034773
+14.956010	-0.043093	-0.059851	9.851487	0.044766	0.086600	-0.036372
+14.956992	-0.033517	-0.045487	9.782060	0.045165	0.087533	-0.035839
+14.958029	-0.023940	-0.011970	9.844305	0.047564	0.087133	-0.035839
+14.959015	-0.045487	-0.011970	9.777271	0.048496	0.087666	-0.037838
+14.959949	0.019152	-0.033517	9.817970	0.047697	0.090997	-0.035173
+14.961007	-0.002394	0.014364	9.760513	0.047164	0.091796	-0.035839
+14.962013	0.011970	-0.002394	9.803606	0.045165	0.087666	-0.037305
+14.962969	0.038305	0.004788	9.841911	0.046231	0.087799	-0.036239
+14.963966	0.059851	0.043093	9.899368	0.046498	0.087933	-0.037038
+14.964962	0.038305	0.000000	9.873033	0.045698	0.086334	-0.036505
+14.966013	-0.028729	-0.057457	9.817970	0.047297	0.087799	-0.035173
+14.967010	0.007182	-0.016758	9.806000	0.047564	0.088998	-0.035306
+14.967964	0.016758	-0.011970	9.755725	0.049296	0.088199	-0.034507
+14.969006	-0.016758	0.028729	9.729391	0.047697	0.088332	-0.038637
+14.970007	0.009576	0.004788	9.719814	0.046364	0.087799	-0.040236
+14.971014	0.050275	0.023940	9.794030	0.044233	0.085801	-0.035706
+14.972011	-0.004788	0.071821	9.849093	0.043966	0.086867	-0.034374
+14.973013	0.019152	-0.009576	9.815576	0.044100	0.087666	-0.035306
+14.973964	0.021546	-0.045487	9.784454	0.045832	0.088199	-0.035573
+14.975012	-0.019152	-0.093368	9.827546	0.047430	0.090064	-0.038637
+14.976010	-0.023940	-0.062245	9.839517	0.047963	0.092063	-0.036372
+14.976993	-0.021546	0.007182	9.789242	0.047830	0.092462	-0.035972
+14.977995	0.007182	-0.009576	9.817970	0.047297	0.089132	-0.037305
+14.979012	0.038305	-0.045487	9.794030	0.049828	0.087266	-0.036905
+14.979975	0.002394	-0.014364	9.820364	0.048496	0.085401	-0.035839
+14.981013	-0.047881	-0.059851	9.810788	0.044100	0.085268	-0.037704
+14.982014	-0.002394	-0.031123	9.861063	0.044100	0.086734	-0.039969
+14.983010	0.071821	-0.004788	9.839517	0.044766	0.086600	-0.039969
+14.984013	0.055063	0.000000	9.863457	0.047697	0.087266	-0.035040
+14.984995	0.031123	0.043093	9.849093	0.048496	0.088998	-0.034640
+14.986015	0.011970	0.016758	9.940066	0.048896	0.089398	-0.036239
+14.986993	-0.014364	0.023940	9.875427	0.048763	0.087933	-0.036239
+14.987998	-0.016758	0.021546	9.782060	0.048230	0.087666	-0.035839
+14.989013	-0.043093	-0.011970	9.717420	0.048363	0.087666	-0.035839
+14.989977	0.000000	-0.028729	9.767695	0.047963	0.085801	-0.038904
+14.991006	0.059851	-0.069427	9.880215	0.047297	0.086201	-0.036505
+14.992012	0.052669	-0.016758	9.875427	0.047697	0.089531	-0.034640
+14.993011	0.038305	-0.031123	9.806000	0.047430	0.088732	-0.036239
+14.994014	-0.009576	0.004788	9.784454	0.045299	0.086467	-0.037305
+14.994964	0.019152	-0.047881	9.765301	0.044499	0.086467	-0.036106
+14.996011	-0.007182	-0.019152	9.782060	0.046231	0.087000	-0.034507
+14.997002	0.000000	0.028729	9.798818	0.048230	0.087799	-0.035839
+14.998017	-0.055063	0.007182	9.774877	0.047297	0.086600	-0.038770
+14.999012	-0.004788	0.023940	9.887397	0.045965	0.087000	-0.039436
+14.999947	0.004788	-0.004788	9.863457	0.045165	0.086734	-0.036372
+15.001008	0.062245	-0.019152	9.808394	0.047297	0.089132	-0.032242
diff --git a/src/test/data/IMU/imu_static_biasNull.txt b/src/test/data/IMU/imu_static_biasNull.txt
new file mode 100644
index 0000000000000000000000000000000000000000..ddc5fdeabf5a2a582fb38750e97a7158efd7dc61
--- /dev/null
+++ b/src/test/data/IMU/imu_static_biasNull.txt
@@ -0,0 +1,1003 @@
+0.0000000000000000	0.0000000000000000	0.0000000000000000	1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0000000000000000	0.0000000000000000	0.0000000000000435	1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000001137	
+0.0000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5209999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5229999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5249999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5269999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5289999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5309999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5329999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5349999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5369999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5389999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5409999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5429999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5449999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5469999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5489999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5509999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5529999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5549999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5569999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5580000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5589999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5600000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5609999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5620000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5629999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5640000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5649999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5660000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5669999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5680000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5700000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5720000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5740000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5760000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5780000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5800000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5820000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6499999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6519999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6539999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6559999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6579999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6599999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6619999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6639999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6659999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6679999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6699999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6719999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6739999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6759999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6779999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6799999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6819999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6830000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6839999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6850000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6859999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6870000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6879999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6890000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6899999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6910000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6919999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6930000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6950000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6970000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6990000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7010000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7030000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7050000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7070000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7090000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7110000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7929999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7949999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7969999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7989999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8009999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8029999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8049999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8069999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8080000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8089999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8100000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8109999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8120000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8129999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8140000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8149999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8160000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8169999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8180000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8200000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8220000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8240000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9279999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9299999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9319999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9330000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9339999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9350000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9359999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9370000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9379999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9390000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9399999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9409999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9419999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9429999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.0000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
diff --git a/src/test/data/IMU/imu_static_biasNull.txt~ b/src/test/data/IMU/imu_static_biasNull.txt~
new file mode 100644
index 0000000000000000000000000000000000000000..ddc5fdeabf5a2a582fb38750e97a7158efd7dc61
--- /dev/null
+++ b/src/test/data/IMU/imu_static_biasNull.txt~
@@ -0,0 +1,1003 @@
+0.0000000000000000	0.0000000000000000	0.0000000000000000	1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0000000000000000	0.0000000000000000	0.0000000000000435	1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000001137	
+0.0000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5209999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5229999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5249999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5269999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5289999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5309999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5329999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5349999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5369999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5389999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5409999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5429999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5449999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5469999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5489999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5509999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5529999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5549999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5569999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5580000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5589999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5600000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5609999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5620000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5629999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5640000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5649999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5660000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5669999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5680000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5700000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5720000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5740000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5760000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5780000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5800000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5820000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6499999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6519999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6539999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6559999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6579999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6599999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6619999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6639999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6659999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6679999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6699999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6719999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6739999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6759999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6779999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6799999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6819999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6830000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6839999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6850000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6859999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6870000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6879999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6890000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6899999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6910000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6919999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6930000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6950000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6970000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6990000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7010000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7030000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7050000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7070000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7090000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7110000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7929999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7949999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7969999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7989999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8009999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8029999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8049999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8069999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8080000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8089999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8100000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8109999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8120000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8129999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8140000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8149999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8160000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8169999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8180000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8200000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8220000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8240000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8280000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8300000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8320000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8330000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8340000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8350000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8360000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8370000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8380000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8390000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8400000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8410000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8420000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8430000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9010000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9020000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9030000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9040000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9050000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9060000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9070000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9080000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9090000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9100000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9110000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9120000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9130000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9140000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9150000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9160000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9170000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9180000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9190000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9200000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9210000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9220000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9230000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9240000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9250000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9260000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9270000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9279999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9290000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9299999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9310000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9319999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9330000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9339999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9350000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9359999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9370000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9379999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9390000000000001	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9399999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9409999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9419999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9429999999999999	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9440000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9450000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9460000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9470000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9480000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9490000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9500000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9510000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9520000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9530000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9540000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9550000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9560000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9570000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9580000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9590000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9600000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9610000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9620000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9630000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9640000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9650000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9660000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9670000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9680000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9690000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9700000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9710000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9720000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9730000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9740000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9750000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9760000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9770000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9780000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9790000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9800000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9810000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9820000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9830000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9840000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9850000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9860000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9870000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9880000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9890000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9900000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9910000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9920000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9930000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9940000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9950000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9960000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9970000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9980000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9990000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.0000000000000000	0.0000000000000000	0.0000000000000000	9.8000000000000007	0.0000000000000000	0.0000000000000000	0.0000000000000000	
diff --git a/src/test/data/IMU/odom1Rotation.txt b/src/test/data/IMU/odom1Rotation.txt
new file mode 100644
index 0000000000000000000000000000000000000000..febc43adc08ade826f64068ac722c7e5d5a2d7d4
--- /dev/null
+++ b/src/test/data/IMU/odom1Rotation.txt
@@ -0,0 +1,2 @@
+1.097372	0	0	0	0	0	0
+4.091482	0	0	0	0	0	0
diff --git a/src/test/data/IMU/odom_check_BiasedNoisyComplex.txt b/src/test/data/IMU/odom_check_BiasedNoisyComplex.txt
new file mode 100644
index 0000000000000000000000000000000000000000..8af1b0cb0841cdb801a0c61e40e37f8d0386d86b
--- /dev/null
+++ b/src/test/data/IMU/odom_check_BiasedNoisyComplex.txt
@@ -0,0 +1,6005 @@
+0.0010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0030000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0040000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0050000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0070000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0080000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0090000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0100000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0120000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0130000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0160000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0180000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0200000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0210000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0230000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0250000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0260000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0280000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0300000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0310000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0330000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0350000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0360000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0370000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0380000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0390000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0400000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0420000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0430000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0440000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0450000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0460000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0470000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0490000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0500000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0510000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0540000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0550000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0560000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0570000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0580000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0590000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0600000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0610000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0620000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0630000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0650000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0660000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0670000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0690000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0700000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0710000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0720000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0740000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0750000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0760000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0770000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0820000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0830000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0870000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0920000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0930000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0940000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0970000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.0990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1000000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1030000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1040000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1050000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1070000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1080000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1100000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1120000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1130000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1160000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1180000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1200000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1210000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1230000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1250000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1260000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1300000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1310000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1330000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1350000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1370000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1390000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1400000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1420000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1430000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1440000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1450000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1460000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1470000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1490000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1500000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1510000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1540000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1550000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1560000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1570000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1580000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1590000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1600000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1620000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1630000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1650000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1660000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1670000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1690000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1700000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1720000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1740000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1750000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1770000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1820000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1830000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1870000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1920000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1930000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1940000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1970000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.1990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2030000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2040000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2050000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2070000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2080000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2100000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2110000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2120000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2130000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2160000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2180000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2200000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2210000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2230000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2250000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2260000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2300000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2310000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2330000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2340000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2350000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2370000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2390000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2400000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2420000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2430000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2440000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2450000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2460000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2470000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2490000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2500000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2510000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2520000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2540000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2550000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2560000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2570000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2580000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2590000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2600000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2620000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2630000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2650000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2660000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2670000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2680000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2690000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2700000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2720000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2730000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2740000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2750000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2770000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2810000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2820000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2830000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2840000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2850000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2870000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2900000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2920000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2930000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2940000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2950000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2970000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2980000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.2990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3000000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3020000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3030000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3040000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3050000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3060000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3070000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3080000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3100000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3110000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3120000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3130000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3140000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3150000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3160000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3170000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3180000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3190000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3200000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3210000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3230000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3250000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3260000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3270000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3300000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3310000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3330000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3350000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3370000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3390000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3400000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3420000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3430000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3440000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3450000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3460000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3470000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3490000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3500000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3510000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3530000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3540000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3550000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3560000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3570000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3580000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3590000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3600000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3620000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3630000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3640000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3650000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3660000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3670000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3690000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3700000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3720000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3740000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3750000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3760000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3770000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3800000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3810000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3820000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3830000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3850000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3860000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3870000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3880000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3900000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3920000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3930000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3940000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3950000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3970000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3980000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.3990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4000000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4020000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4030000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4040000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4050000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4070000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4080000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4100000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4120000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4130000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4140000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4160000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4180000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4200000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4210000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4220000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4230000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4240000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4250000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4260000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4270000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4290000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4300000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4310000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4330000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4350000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4370000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4390000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4400000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4410000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4420000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4430000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4440000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4450000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4460000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4470000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4480000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4490000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4500000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4510000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4520000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4540000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4550000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4560000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4570000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4580000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4590000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4600000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4620000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4630000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4650000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4660000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4670000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4690000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4700000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4720000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4740000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4750000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4770000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4790000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4820000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4830000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4870000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4920000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4930000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4940000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4970000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.4990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5030000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5040000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5050000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5070000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5080000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5100000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5120000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5130000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5160000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5170000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5180000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5200000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5210000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5230000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5240000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5250000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5260000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5300000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5310000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5330000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5350000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5360000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5370000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5390000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5400000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5420000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5430000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5440000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5450000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5460000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5470000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5490000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5500000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5510000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5530000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5540000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5550000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5560000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5570000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5580000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5590000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5600000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5610000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5620000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5630000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5640000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5650000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5660000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5670000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5680000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5690000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5700000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5710000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5720000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5730000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5740000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5750000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5760000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5770000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5790000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5820000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5830000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5870000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5920000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5930000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5940000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5960000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5970000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.5990000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6030000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6040000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6050000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6070000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6080000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6100000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6120000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6130000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6160000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6180000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6200000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6210000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6230000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6250000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6260000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6300000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6310000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6330000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000002	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6350000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6370000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6390000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6400000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6420000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6430000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6440000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6450000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6460000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6470000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6490000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6500000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6510000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6540000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6550000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6560000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6570000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6580000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6590000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6600000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6620000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6630000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6650000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6660000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6670000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6690000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6700000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6720000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6740000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6750000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6770000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6780000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6800000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6820000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6830000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6840000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6850000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6860000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6870000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6880000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6890000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6900000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6910000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6920000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6930000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6940000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6950000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6960000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6970000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6980000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.6990000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7000000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7010000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7020000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7030000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7040000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7050000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7070000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7080000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7100000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7120000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7130000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7160000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7180000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7200000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7210000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7230000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7250000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7260000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7280000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7300000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7310000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7320000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7330000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7350000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7370000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7390000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7400000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7410000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7420000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7430000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7440000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7450000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7460000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7470000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7490000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7500000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7510000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7540000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7550000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7560000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7570000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7580000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7590000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7600000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7620000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7630000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7650000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7660000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7670000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7690000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7700000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7720000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7740000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7750000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7770000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7820000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7830000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7870000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7890000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7920000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7930000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7940000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7970000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.7990000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8000000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8030000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8040000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8050000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8060000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8070000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8080000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8090000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8100000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8110000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8120000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8130000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8140000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8150000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8160000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8170000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8180000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8190000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8200000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8210000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8220000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8230000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8240000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8250000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8260000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8270000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8280000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8290000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8300000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8310000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8320000000000001	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8330000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8340000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8350000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8360000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8370000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8380000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8390000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8400000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8410000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8420000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8430000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8440000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8450000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8460000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8470000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8480000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8490000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8500000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8510000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8520000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8530000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8540000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8550000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8560000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8570000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8580000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8590000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8600000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8610000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8620000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8630000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8650000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8660000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8670000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8690000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8700000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8720000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8740000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8750000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8770000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8820000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8830000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8840000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8870000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8920000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8930000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8940000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8970000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.8990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9010000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9020000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9030000000000000	0.0000000000000000	0.0000000000000000	-0.0000000000000004	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9040000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9050000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9060000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9070000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9080000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9090000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9100000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9110000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000018	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9120000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9130000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9140000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9150000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9160000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9170000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9180000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9190000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9200000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9210000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9220000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9230000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9240000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9250000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9260000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9270000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9280000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000018	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9290000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9300000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9310000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9320000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9330000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9340000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9350000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9360000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9370000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9380000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9390000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9400000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9410000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9420000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9430000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9440000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9450000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9460000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9470000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9480000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9490000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9500000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9510000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9520000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9530000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9540000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9550000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9560000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9570000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9580000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9590000000000001	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9600000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000018	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9610000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9620000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9630000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9640000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9650000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9660000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9670000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9680000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9690000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9700000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9710000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9720000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9730000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9740000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9750000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9760000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9770000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9780000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9790000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9800000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9810000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9820000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9830000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9840000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9850000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9860000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9870000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9880000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9890000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9900000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9910000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9920000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9930000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9940000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9950000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9960000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9970000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9980000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+0.9990000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.0000000000000000	0.0000000000000000	0.0000000000000000	0.0000000000000009	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.0010000000000001	0.0000000025000000	0.0000000010000000	0.0000000044999995	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0020000000000000	0.0000000075000000	0.0000000030282644	0.0000000134936734	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0030000000000001	0.0000000125000000	0.0000000050847732	0.0000000224809273	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0040000000000000	0.0000000175000000	0.0000000071695062	0.0000000314616805	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0050000000000001	0.0000000225000000	0.0000000092824426	0.0000000404358357	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0060000000000000	0.0000000275000000	0.0000000114235617	0.0000000494033134	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0070000000000001	0.0000000325000000	0.0000000135928424	0.0000000583640156	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0080000000000000	0.0000000375000000	0.0000000157902632	0.0000000673178621	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0090000000000001	0.0000000425000000	0.0000000180158024	0.0000000762647580	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0100000000000000	0.0000000475000000	0.0000000202694382	0.0000000852046225	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0110000000000001	0.0000000525000000	0.0000000225511480	0.0000000941373562	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0120000000000000	0.0000000575000000	0.0000000248609098	0.0000001030628849	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0130000000000001	0.0000000625000000	0.0000000271987003	0.0000001119811061	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0140000000000000	0.0000000675000000	0.0000000295644969	0.0000001208919466	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0150000000000001	0.0000000725000000	0.0000000319582757	0.0000001297953040	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0160000000000000	0.0000000775000000	0.0000000343800136	0.0000001386911019	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0170000000000001	0.0000000825000000	0.0000000368296863	0.0000001475792444	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0180000000000000	0.0000000875000000	0.0000000393072699	0.0000001564596501	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0190000000000001	0.0000000925000000	0.0000000418127397	0.0000001653322250	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0200000000000000	0.0000000975000000	0.0000000443460714	0.0000001741968888	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0210000000000001	0.0000001025000000	0.0000000469072394	0.0000001830535470	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0220000000000000	0.0000001075000000	0.0000000494962189	0.0000001919021177	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0230000000000001	0.0000001125000000	0.0000000521129840	0.0000002007425075	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0240000000000000	0.0000001175000000	0.0000000547575095	0.0000002095746392	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0249999999999999	0.0000001225000000	0.0000000574297684	0.0000002183984144	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0260000000000000	0.0000001275000000	0.0000000601297349	0.0000002272137516	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0269999999999999	0.0000001325000000	0.0000000628573824	0.0000002360205652	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0280000000000000	0.0000001375000000	0.0000000656126835	0.0000002448187632	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0289999999999999	0.0000001425000000	0.0000000683956116	0.0000002536082638	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0300000000000000	0.0000001475000000	0.0000000712061387	0.0000002623889771	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0309999999999999	0.0000001525000000	0.0000000740442376	0.0000002711608197	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0320000000000000	0.0000001575000000	0.0000000769098797	0.0000002799236993	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0329999999999999	0.0000001625000000	0.0000000798030373	0.0000002886775363	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0340000000000000	0.0000001675000000	0.0000000827236812	0.0000002974222378	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0349999999999999	0.0000001725000000	0.0000000856717835	0.0000003061577253	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0360000000000000	0.0000001775000000	0.0000000886473140	0.0000003148839034	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0369999999999999	0.0000001825000000	0.0000000916502442	0.0000003236006940	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0380000000000000	0.0000001875000000	0.0000000946805438	0.0000003323080037	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0389999999999999	0.0000001925000000	0.0000000977381837	0.0000003410057554	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0400000000000000	0.0000001975000000	0.0000001008231328	0.0000003496938534	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0409999999999999	0.0000002025000000	0.0000001039353616	0.0000003583722217	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0420000000000000	0.0000002075000000	0.0000001070748382	0.0000003670407649	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0429999999999999	0.0000002125000000	0.0000001102415330	0.0000003756994072	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0440000000000000	0.0000002175000000	0.0000001134354137	0.0000003843480552	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0449999999999999	0.0000002225000000	0.0000001166564492	0.0000003929866281	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0460000000000000	0.0000002275000000	0.0000001199046073	0.0000004016150363	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0469999999999999	0.0000002325000000	0.0000001231798570	0.0000004102332025	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0480000000000000	0.0000002375000000	0.0000001264821643	0.0000004188410306	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0489999999999999	0.0000002425000000	0.0000001298114987	0.0000004274384489	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0500000000000000	0.0000002475000000	0.0000001331678254	0.0000004360253604	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0509999999999999	0.0000002525000000	0.0000001365511121	0.0000004446016858	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0520000000000000	0.0000002575000000	0.0000001399613256	0.0000004531673407	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0529999999999999	0.0000002625000000	0.0000001433984323	0.0000004617222416	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0540000000000000	0.0000002675000000	0.0000001468623974	0.0000004702662992	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0549999999999999	0.0000002725000000	0.0000001503531876	0.0000004787994337	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0560000000000000	0.0000002775000000	0.0000001538707682	0.0000004873215595	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0569999999999999	0.0000002825000000	0.0000001574151044	0.0000004958325927	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0580000000000001	0.0000002875000000	0.0000001609861611	0.0000005043324478	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0589999999999999	0.0000002925000000	0.0000001645839036	0.0000005128210440	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0600000000000001	0.0000002975000000	0.0000001682082955	0.0000005212982935	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0609999999999999	0.0000003025000000	0.0000001718593022	0.0000005297641180	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0620000000000001	0.0000003075000000	0.0000001755368864	0.0000005382184275	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0629999999999999	0.0000003125000000	0.0000001792410131	0.0000005466611458	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0640000000000001	0.0000003175000000	0.0000001829716439	0.0000005550921794	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0649999999999999	0.0000003225000000	0.0000001867287444	0.0000005635114579	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0660000000000001	0.0000003275000000	0.0000001905122750	0.0000005719188853	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0669999999999999	0.0000003325000000	0.0000001943222012	0.0000005803143922	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0680000000000001	0.0000003375000000	0.0000001981584820	0.0000005886978803	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0690000000000000	0.0000003425000000	0.0000002020210828	0.0000005970692822	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0700000000000001	0.0000003475000000	0.0000002059099631	0.0000006054285034	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.0710000000000000	0.0000003525000000	0.0000002098250860	0.0000006137754687	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0720000000000001	0.0000003575000000	0.0000002137664121	0.0000006221100919	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0730000000000000	0.0000003625000000	0.0000002177339030	0.0000006304322936	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0740000000000001	0.0000003675000000	0.0000002217275183	0.0000006387419861	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0750000000000000	0.0000003725000000	0.0000002257472208	0.0000006470390963	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0760000000000001	0.0000003775000000	0.0000002297929683	0.0000006553235325	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0770000000000000	0.0000003825000000	0.0000002338647232	0.0000006635952217	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0780000000000001	0.0000003875000000	0.0000002379624435	0.0000006718540760	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0790000000000000	0.0000003925000000	0.0000002420860902	0.0000006801000183	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0800000000000001	0.0000003975000000	0.0000002462356207	0.0000006883329609	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0810000000000000	0.0000004025000000	0.0000002504109967	0.0000006965528323	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0820000000000001	0.0000004075000000	0.0000002546121746	0.0000007047595422	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0830000000000000	0.0000004125000000	0.0000002588391144	0.0000007129530151	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0840000000000001	0.0000004175000000	0.0000002630917730	0.0000007211331654	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0850000000000000	0.0000004225000000	0.0000002673701100	0.0000007292999177	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.0860000000000001	0.0000004275000000	0.0000002716740821	0.0000007374531875	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.0870000000000000	0.0000004325000000	0.0000002760036482	0.0000007455928998	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0880000000000001	0.0000004375000000	0.0000002803587627	0.0000007537189633	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.0890000000000000	0.0000004425000000	0.0000002847393859	0.0000007618313101	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0900000000000001	0.0000004475000000	0.0000002891454725	0.0000007699298526	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.0910000000000000	0.0000004525000000	0.0000002935769804	0.0000007780145155	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.0920000000000001	0.0000004575000000	0.0000002980338639	0.0000007860852123	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0930000000000000	0.0000004625000000	0.0000003025160815	0.0000007941418722	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0940000000000001	0.0000004675000000	0.0000003070235860	0.0000008021844054	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0950000000000000	0.0000004725000000	0.0000003115563366	0.0000008102127448	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0960000000000001	0.0000004775000000	0.0000003161142847	0.0000008182267985	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0970000000000000	0.0000004825000000	0.0000003206973890	0.0000008262264993	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0980000000000001	0.0000004875000000	0.0000003253056006	0.0000008342117566	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.0990000000000000	0.0000004925000000	0.0000003299388772	0.0000008421825018	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1000000000000001	0.0000004975000000	0.0000003345971708	0.0000008501386487	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1010000000000000	0.0000005025000000	0.0000003392804377	0.0000008580801263	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1020000000000001	0.0000005075000000	0.0000003439886280	0.0000008660068444	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1030000000000000	0.0000005125000000	0.0000003487217000	0.0000008739187400	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1040000000000001	0.0000005175000000	0.0000003534796033	0.0000008818157231	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1050000000000000	0.0000005225000000	0.0000003582622922	0.0000008896977200	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1060000000000001	0.0000005275000000	0.0000003630697194	0.0000008975646526	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1070000000000000	0.0000005325000000	0.0000003679018384	0.0000009054164458	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1080000000000001	0.0000005375000000	0.0000003727585996	0.0000009132530169	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1090000000000000	0.0000005425000000	0.0000003776399574	0.0000009210742950	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1100000000000001	0.0000005475000000	0.0000003825458606	0.0000009288801943	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1110000000000000	0.0000005525000000	0.0000003874762642	0.0000009366706475	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1120000000000001	0.0000005575000000	0.0000003924311161	0.0000009444455684	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1130000000000000	0.0000005625000000	0.0000003974103713	0.0000009522048906	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1140000000000001	0.0000005675000000	0.0000004024139763	0.0000009599485255	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1150000000000000	0.0000005725000000	0.0000004074418858	0.0000009676764080	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1160000000000001	0.0000005775000000	0.0000004124940465	0.0000009753884522	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1170000000000000	0.0000005825000000	0.0000004175704123	0.0000009830845915	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1180000000000001	0.0000005875000000	0.0000004226709294	0.0000009907647404	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1190000000000000	0.0000005925000000	0.0000004277955506	0.0000009984288315	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1200000000000001	0.0000005975000000	0.0000004329442230	0.0000010060767828	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1210000000000000	0.0000006025000000	0.0000004381168974	0.0000010137085233	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1220000000000001	0.0000006075000000	0.0000004433135202	0.0000010213239711	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1230000000000000	0.0000006125000000	0.0000004485340449	0.0000010289230627	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1240000000000001	0.0000006175000000	0.0000004537784142	0.0000010365057093	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1250000000000000	0.0000006225000000	0.0000004590465814	0.0000010440718483	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1260000000000001	0.0000006275000000	0.0000004643384905	0.0000010516213952	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1270000000000000	0.0000006325000000	0.0000004696540930	0.0000010591542844	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1280000000000001	0.0000006375000000	0.0000004749933326	0.0000010666704325	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1290000000000000	0.0000006425000000	0.0000004803561596	0.0000010741697726	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1300000000000001	0.0000006475000000	0.0000004857425190	0.0000010816522255	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1310000000000000	0.0000006525000000	0.0000004911523609	0.0000010891177252	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1320000000000001	0.0000006575000000	0.0000004965856259	0.0000010965661840	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1330000000000000	0.0000006625000000	0.0000005020422677	0.0000011039975451	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1340000000000001	0.0000006675000000	0.0000005075222265	0.0000011114117217	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1350000000000000	0.0000006725000000	0.0000005130254526	0.0000011188086508	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1360000000000001	0.0000006775000000	0.0000005185518866	0.0000011261882475	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1370000000000000	0.0000006825000000	0.0000005241014801	0.0000011335504530	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1380000000000001	0.0000006875000000	0.0000005296741730	0.0000011408951828	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1390000000000000	0.0000006925000000	0.0000005352699148	0.0000011482223742	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1400000000000001	0.0000006975000000	0.0000005408886444	0.0000011555319421	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1410000000000000	0.0000007025000000	0.0000005465303141	0.0000011628238313	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1420000000000001	0.0000007075000000	0.0000005521948612	0.0000011700979546	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1430000000000000	0.0000007125000000	0.0000005578822339	0.0000011773542488	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1440000000000001	0.0000007175000000	0.0000005635923737	0.0000011845926376	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1450000000000000	0.0000007225000000	0.0000005693252264	0.0000011918130540	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1460000000000001	0.0000007275000000	0.0000005750807335	0.0000011990154225	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1470000000000000	0.0000007325000000	0.0000005808588410	0.0000012061996782	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1480000000000001	0.0000007375000000	0.0000005866594875	0.0000012133657411	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1490000000000000	0.0000007425000000	0.0000005924826203	0.0000012205135495	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1500000000000001	0.0000007475000000	0.0000005983281777	0.0000012276430244	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1510000000000000	0.0000007525000000	0.0000006041961061	0.0000012347541037	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1520000000000001	0.0000007575000000	0.0000006100863440	0.0000012418467103	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1530000000000000	0.0000007625000000	0.0000006159988367	0.0000012489207806	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1539999999999999	0.0000007675000000	0.0000006219335229	0.0000012559762393	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1550000000000000	0.0000007725000000	0.0000006278903441	0.0000012630130169	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1559999999999999	0.0000007775000000	0.0000006338692448	0.0000012700310500	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1570000000000000	0.0000007825000000	0.0000006398701617	0.0000012770302613	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1579999999999999	0.0000007875000000	0.0000006458930392	0.0000012840105888	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1590000000000000	0.0000007925000000	0.0000006519378149	0.0000012909719577	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1599999999999999	0.0000007975000000	0.0000006580044326	0.0000012979143061	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1610000000000000	0.0000008025000000	0.0000006640928277	0.0000013048375563	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1619999999999999	0.0000008075000000	0.0000006702029457	0.0000013117416506	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1630000000000000	0.0000008125000000	0.0000006763347195	0.0000013186265086	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.1639999999999999	0.0000008175000000	0.0000006824880967	0.0000013254920764	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1650000000000000	0.0000008225000000	0.0000006886630090	0.0000013323382733	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1659999999999999	0.0000008275000000	0.0000006948594012	0.0000013391650417	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1670000000000000	0.0000008325000000	0.0000007010772069	0.0000013459723049	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1679999999999999	0.0000008375000000	0.0000007073163712	0.0000013527600071	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1690000000000000	0.0000008425000000	0.0000007135768254	0.0000013595280690	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1699999999999999	0.0000008475000000	0.0000007198585138	0.0000013662764341	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1710000000000000	0.0000008525000000	0.0000007261613687	0.0000013730050263	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1719999999999999	0.0000008575000000	0.0000007324853349	0.0000013797137910	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1730000000000000	0.0000008625000000	0.0000007388303420	0.0000013864026485	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1739999999999999	0.0000008675000000	0.0000007451963357	0.0000013930715467	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1750000000000000	0.0000008725000000	0.0000007515832441	0.0000013997204047	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.1759999999999999	0.0000008775000000	0.0000007579910139	0.0000014063491728	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1770000000000000	0.0000008825000000	0.0000007644195728	0.0000014129577712	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1779999999999999	0.0000008875000000	0.0000007708688645	0.0000014195461459	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1790000000000000	0.0000008925000000	0.0000007773388195	0.0000014261142225	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1799999999999999	0.0000008975000000	0.0000007838293799	0.0000014326619457	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1810000000000000	0.0000009025000000	0.0000007903404758	0.0000014391892416	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1819999999999999	0.0000009075000000	0.0000007968720482	0.0000014456960543	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1830000000000001	0.0000009125000000	0.0000008034240267	0.0000014521823100	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1839999999999999	0.0000009175000000	0.0000008099963543	0.0000014586479568	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1850000000000001	0.0000009225000000	0.0000008165889571	0.0000014650929168	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1859999999999999	0.0000009275000000	0.0000008232017788	0.0000014715171397	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1870000000000001	0.0000009325000000	0.0000008298347475	0.0000014779205525	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1879999999999999	0.0000009375000000	0.0000008364878022	0.0000014843030982	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1890000000000001	0.0000009425000000	0.0000008431608730	0.0000014906647078	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1899999999999999	0.0000009475000000	0.0000008498538999	0.0000014970053270	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1910000000000001	0.0000009525000000	0.0000008565668099	0.0000015033248831	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1919999999999999	0.0000009575000000	0.0000008632995434	0.0000015096233236	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1930000000000001	0.0000009625000000	0.0000008700520270	0.0000015159005760	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1940000000000000	0.0000009675000000	0.0000008768242022	0.0000015221565902	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1950000000000001	0.0000009725000000	0.0000008836159940	0.0000015283912928	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1960000000000000	0.0000009775000000	0.0000008904273419	0.0000015346046313	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.1970000000000001	0.0000009825000000	0.0000008972581728	0.0000015407965364	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.1980000000000000	0.0000009875000000	0.0000009041084267	0.0000015469669574	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.1990000000000001	0.0000009925000000	0.0000009109780276	0.0000015531158215	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2000000000000000	0.0000009975000000	0.0000009178669150	0.0000015592430782	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2010000000000001	0.0000010025000000	0.0000009247750148	0.0000015653486586	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.2020000000000000	0.0000010075000000	0.0000009317022650	0.0000015714325111	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2030000000000001	0.0000010125000000	0.0000009386485905	0.0000015774945661	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2040000000000000	0.0000010175000000	0.0000009456139294	0.0000015835347732	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2050000000000001	0.0000010225000000	0.0000009525982065	0.0000015895530637	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2060000000000000	0.0000010275000000	0.0000009596013599	0.0000015955493879	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2070000000000001	0.0000010325000000	0.0000009666233117	0.0000016015236749	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2080000000000000	0.0000010375000000	0.0000009736640035	0.0000016074758801	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2090000000000001	0.0000010425000000	0.0000009807233546	0.0000016134059299	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2100000000000000	0.0000010475000000	0.0000009878013048	0.0000016193137785	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2110000000000001	0.0000010525000000	0.0000009948977774	0.0000016251993583	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2120000000000000	0.0000010575000000	0.0000010020127065	0.0000016310626167	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2130000000000001	0.0000010625000000	0.0000010091460193	0.0000016369034926	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2140000000000000	0.0000010675000000	0.0000010162976485	0.0000016427219323	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2150000000000001	0.0000010725000000	0.0000010234675182	0.0000016485178716	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.2160000000000000	0.0000010775000000	0.0000010306555643	0.0000016542912616	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2170000000000001	0.0000010825000000	0.0000010378617103	0.0000016600420386	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2180000000000000	0.0000010875000000	0.0000010450858890	0.0000016657701504	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2190000000000001	0.0000010925000000	0.0000010523280243	0.0000016714755350	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2200000000000000	0.0000010975000000	0.0000010595880526	0.0000016771581452	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2210000000000001	0.0000011025000000	0.0000010668658933	0.0000016828179143	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2220000000000000	0.0000011075000000	0.0000010741614827	0.0000016884547963	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2230000000000001	0.0000011125000000	0.0000010814747398	0.0000016940687248	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2240000000000000	0.0000011175000000	0.0000010888056027	0.0000016996596565	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2250000000000001	0.0000011225000000	0.0000010961539898	0.0000017052275253	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2260000000000000	0.0000011275000000	0.0000011035198364	0.0000017107722855	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2270000000000001	0.0000011325000000	0.0000011109030610	0.0000017162938721	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2280000000000000	0.0000011375000000	0.0000011183036007	0.0000017217922422	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2290000000000001	0.0000011425000000	0.0000011257213728	0.0000017272673302	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2300000000000000	0.0000011475000000	0.0000011331563135	0.0000017327190931	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2310000000000001	0.0000011525000000	0.0000011406083405	0.0000017381474668	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2320000000000000	0.0000011575000000	0.0000011480773879	0.0000017435524064	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2330000000000001	0.0000011625000000	0.0000011555633763	0.0000017489338523	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.2340000000000000	0.0000011675000000	0.0000011630662352	0.0000017542917549	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2350000000000001	0.0000011725000000	0.0000011705858878	0.0000017596260584	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.2360000000000000	0.0000011775000000	0.0000011781222646	0.0000017649367155	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2370000000000001	0.0000011825000000	0.0000011856752836	0.0000017702236651	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2380000000000000	0.0000011875000000	0.0000011932448808	0.0000017754868669	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2390000000000001	0.0000011925000000	0.0000012008309688	0.0000017807262549	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2400000000000000	0.0000011975000000	0.0000012084334839	0.0000017859417895	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2410000000000001	0.0000012025000000	0.0000012160523439	0.0000017911334117	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2420000000000000	0.0000012075000000	0.0000012236874788	0.0000017963010756	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2430000000000001	0.0000012125000000	0.0000012313388081	0.0000018014447249	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2440000000000000	0.0000012175000000	0.0000012390062614	0.0000018065643141	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2450000000000001	0.0000012225000000	0.0000012466897577	0.0000018116597871	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2460000000000000	0.0000012275000000	0.0000012543892266	0.0000018167310994	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.2470000000000001	0.0000012325000000	0.0000012621045873	0.0000018217781958	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.2480000000000000	0.0000012375000000	0.0000012698357687	0.0000018268010318	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2490000000000001	0.0000012425000000	0.0000012775826877	0.0000018317995509	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2500000000000000	0.0000012475000000	0.0000012853452754	0.0000018367737112	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2510000000000001	0.0000012525000000	0.0000012931234491	0.0000018417234579	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2520000000000000	0.0000012575000000	0.0000013009171369	0.0000018466487466	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2530000000000001	0.0000012625000000	0.0000013087262558	0.0000018515495229	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2540000000000000	0.0000012675000000	0.0000013165507364	0.0000018564257459	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2550000000000001	0.0000012725000000	0.0000013243904939	0.0000018612773600	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2560000000000000	0.0000012775000000	0.0000013322454577	0.0000018661043241	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2570000000000001	0.0000012825000000	0.0000013401155438	0.0000018709065841	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2580000000000000	0.0000012875000000	0.0000013480006812	0.0000018756840991	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2590000000000001	0.0000012925000000	0.0000013559007851	0.0000018804368153	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2600000000000000	0.0000012975000000	0.0000013638157854	0.0000018851646933	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2610000000000001	0.0000013025000000	0.0000013717455955	0.0000018898676784	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2620000000000000	0.0000013075000000	0.0000013796901449	0.0000018945457313	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2630000000000001	0.0000013125000000	0.0000013876493476	0.0000018991987990	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2640000000000000	0.0000013175000000	0.0000013956231331	0.0000019038268430	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2650000000000001	0.0000013225000000	0.0000014036114152	0.0000019084298106	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2660000000000000	0.0000013275000000	0.0000014116141207	0.0000019130076616	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2670000000000001	0.0000013325000000	0.0000014196311668	0.0000019175603473	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2680000000000000	0.0000013375000000	0.0000014276624786	0.0000019220878267	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2690000000000001	0.0000013425000000	0.0000014357079713	0.0000019265900500	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2700000000000000	0.0000013475000000	0.0000014437675717	0.0000019310669784	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2710000000000001	0.0000013525000000	0.0000014518411921	0.0000019355185604	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2720000000000000	0.0000013575000000	0.0000014599287636	0.0000019399447617	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2730000000000001	0.0000013625000000	0.0000014680301948	0.0000019443455284	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2740000000000000	0.0000013675000000	0.0000014761454175	0.0000019487208272	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2750000000000001	0.0000013725000000	0.0000014842743390	0.0000019530706041	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2760000000000000	0.0000013775000000	0.0000014924168913	0.0000019573948268	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2770000000000001	0.0000013825000000	0.0000015005729839	0.0000019616934438	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2780000000000000	0.0000013875000000	0.0000015087425443	0.0000019659664195	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2790000000000001	0.0000013925000000	0.0000015169254847	0.0000019702137058	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2800000000000000	0.0000013975000000	0.0000015251217315	0.0000019744352665	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2809999999999999	0.0000014025000000	0.0000015333311990	0.0000019786310562	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2820000000000000	0.0000014075000000	0.0000015415538056	0.0000019828010329	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.2829999999999999	0.0000014125000000	0.0000015497894747	0.0000019869451593	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2840000000000000	0.0000014175000000	0.0000015580381185	0.0000019910633891	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2849999999999999	0.0000014225000000	0.0000015662996657	0.0000019951556897	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2860000000000000	0.0000014275000000	0.0000015745740209	0.0000019992220098	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2869999999999999	0.0000014325000000	0.0000015828611162	0.0000020032623202	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2880000000000000	0.0000014375000000	0.0000015911608602	0.0000020072765732	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2889999999999999	0.0000014425000000	0.0000015994731774	0.0000020112647345	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2900000000000000	0.0000014475000000	0.0000016077979771	0.0000020152267578	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.2909999999999999	0.0000014525000000	0.0000016161351890	0.0000020191626134	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2920000000000000	0.0000014575000000	0.0000016244847204	0.0000020230722542	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2929999999999999	0.0000014625000000	0.0000016328464950	0.0000020269556464	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2940000000000000	0.0000014675000000	0.0000016412204263	0.0000020308127487	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2949999999999999	0.0000014725000000	0.0000016496064378	0.0000020346435275	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2960000000000000	0.0000014775000000	0.0000016580044396	0.0000020384479398	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.2969999999999999	0.0000014825000000	0.0000016664143516	0.0000020422259501	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2980000000000000	0.0000014875000000	0.0000016748360906	0.0000020459775209	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.2989999999999999	0.0000014925000000	0.0000016832695789	0.0000020497026192	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3000000000000000	0.0000014975000000	0.0000016917147227	0.0000020534012005	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3009999999999999	0.0000015025000000	0.0000017001714465	0.0000020570732340	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3020000000000000	0.0000015075000000	0.0000017086396633	0.0000020607186810	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3029999999999999	0.0000015125000000	0.0000017171192943	0.0000020643375088	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3040000000000000	0.0000015175000000	0.0000017256102459	0.0000020679296747	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3049999999999999	0.0000015225000000	0.0000017341124490	0.0000020714951537	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3060000000000000	0.0000015275000000	0.0000017426258024	0.0000020750338983	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3069999999999999	0.0000015325000000	0.0000017511502392	0.0000020785458857	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3080000000000001	0.0000015375000000	0.0000017596856606	0.0000020820310709	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3089999999999999	0.0000015425000000	0.0000017682319962	0.0000020854894293	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3100000000000001	0.0000015475000000	0.0000017767891452	0.0000020889209152	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3109999999999999	0.0000015525000000	0.0000017853570398	0.0000020923255063	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3120000000000001	0.0000015575000000	0.0000017939355843	0.0000020957031613	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3129999999999999	0.0000015625000000	0.0000018025247002	0.0000020990538511	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3140000000000001	0.0000015675000000	0.0000018111242970	0.0000021023775388	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3149999999999999	0.0000015725000000	0.0000018197342989	0.0000021056741976	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3160000000000001	0.0000015775000000	0.0000018283546058	0.0000021089437849	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3169999999999999	0.0000015825000000	0.0000018369851471	0.0000021121862782	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3180000000000001	0.0000015875000000	0.0000018456258344	0.0000021154016431	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3190000000000000	0.0000015925000000	0.0000018542765772	0.0000021185898445	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3200000000000001	0.0000015975000000	0.0000018629372923	0.0000021217508526	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3210000000000000	0.0000016025000000	0.0000018716079007	0.0000021248846401	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3220000000000001	0.0000016075000000	0.0000018802883053	0.0000021279911688	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3230000000000000	0.0000016125000000	0.0000018889784325	0.0000021310704157	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3240000000000001	0.0000016175000000	0.0000018976781845	0.0000021341223429	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3250000000000000	0.0000016225000000	0.0000019063874844	0.0000021371469258	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3260000000000001	0.0000016275000000	0.0000019151062428	0.0000021401441324	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3270000000000000	0.0000016325000000	0.0000019238343762	0.0000021431139347	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3280000000000001	0.0000016375000000	0.0000019325717917	0.0000021460562994	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3290000000000000	0.0000016425000000	0.0000019413184113	0.0000021489712022	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3300000000000001	0.0000016475000000	0.0000019500741445	0.0000021518586121	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3310000000000000	0.0000016525000000	0.0000019588389069	0.0000021547185016	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3320000000000001	0.0000016575000000	0.0000019676126075	0.0000021575508398	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3330000000000000	0.0000016625000000	0.0000019763951671	0.0000021603556032	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3340000000000001	0.0000016675000000	0.0000019851864898	0.0000021631327587	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3350000000000000	0.0000016725000000	0.0000019939864990	0.0000021658822848	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3360000000000001	0.0000016775000000	0.0000020027950966	0.0000021686041478	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3370000000000000	0.0000016825000000	0.0000020116122086	0.0000021712983284	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3380000000000001	0.0000016875000000	0.0000020204377348	0.0000021739647924	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3390000000000000	0.0000016925000000	0.0000020292715977	0.0000021766035190	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3400000000000001	0.0000016975000000	0.0000020381137056	0.0000021792144795	0.0031415926535895	0.0000000000000000	0.0000000000000000	
+1.3410000000000000	0.0000017025000000	0.0000020469639761	0.0000021817976508	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3420000000000001	0.0000017075000000	0.0000020558223105	0.0000021843530014	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3430000000000000	0.0000017125000000	0.0000020646886384	0.0000021868805151	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3440000000000001	0.0000017175000000	0.0000020735628544	0.0000021893801575	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3450000000000000	0.0000017225000000	0.0000020824448859	0.0000021918519118	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3460000000000001	0.0000017275000000	0.0000020913346333	0.0000021942957473	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3470000000000000	0.0000017325000000	0.0000021002320204	0.0000021967116460	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3480000000000001	0.0000017375000000	0.0000021091369468	0.0000021990995775	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3490000000000000	0.0000017425000000	0.0000021180493376	0.0000022014595249	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3500000000000001	0.0000017475000000	0.0000021269690965	0.0000022037914607	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3510000000000000	0.0000017525000000	0.0000021358961369	0.0000022060953625	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3520000000000001	0.0000017575000000	0.0000021448303670	0.0000022083712057	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3530000000000000	0.0000017625000000	0.0000021537717089	0.0000022106189731	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3540000000000001	0.0000017675000000	0.0000021627200623	0.0000022128386365	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3550000000000000	0.0000017725000000	0.0000021716753490	0.0000022150301790	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3560000000000001	0.0000017775000000	0.0000021806374745	0.0000022171935758	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3570000000000000	0.0000017825000000	0.0000021896063566	0.0000022193288089	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3580000000000001	0.0000017875000000	0.0000021985818957	0.0000022214358515	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3590000000000000	0.0000017925000000	0.0000022075640172	0.0000022235146898	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3600000000000001	0.0000017975000000	0.0000022165526174	0.0000022255652960	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3610000000000000	0.0000018025000000	0.0000022255476230	0.0000022275876572	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3620000000000001	0.0000018075000000	0.0000022345489313	0.0000022295817469	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3630000000000000	0.0000018125000000	0.0000022435564653	0.0000022315475509	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3640000000000001	0.0000018175000000	0.0000022525701267	0.0000022334850454	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3650000000000000	0.0000018225000000	0.0000022615898329	0.0000022353942143	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3660000000000001	0.0000018275000000	0.0000022706154867	0.0000022372750349	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3670000000000000	0.0000018325000000	0.0000022796470149	0.0000022391274960	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3680000000000001	0.0000018375000000	0.0000022886843082	0.0000022409515702	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3690000000000000	0.0000018425000000	0.0000022977272930	0.0000022427472463	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3700000000000001	0.0000018475000000	0.0000023067758724	0.0000022445145034	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3710000000000000	0.0000018525000000	0.0000023158299608	0.0000022462533256	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3720000000000001	0.0000018575000000	0.0000023248894641	0.0000022479636937	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3730000000000000	0.0000018625000000	0.0000023339543012	0.0000022496455944	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3740000000000001	0.0000018675000000	0.0000023430243709	0.0000022512990060	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.3750000000000000	0.0000018725000000	0.0000023520995979	0.0000022529239182	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3760000000000001	0.0000018775000000	0.0000023611798772	0.0000022545203087	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3770000000000000	0.0000018825000000	0.0000023702651348	0.0000022560881680	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3780000000000001	0.0000018875000000	0.0000023793552636	0.0000022576274735	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3790000000000000	0.0000018925000000	0.0000023884501921	0.0000022591382176	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3800000000000001	0.0000018975000000	0.0000023975498143	0.0000022606203787	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3810000000000000	0.0000019025000000	0.0000024066540535	0.0000022620739474	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3820000000000001	0.0000019075000000	0.0000024157628113	0.0000022634989059	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3830000000000000	0.0000019125000000	0.0000024248760038	0.0000022648952427	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3840000000000001	0.0000019175000000	0.0000024339935353	0.0000022662629416	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3850000000000000	0.0000019225000000	0.0000024431153199	0.0000022676019907	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3860000000000001	0.0000019275000000	0.0000024522412646	0.0000022689123758	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3870000000000000	0.0000019325000000	0.0000024613712846	0.0000022701940858	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3880000000000001	0.0000019375000000	0.0000024705052815	0.0000022714471050	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3890000000000000	0.0000019425000000	0.0000024796431749	0.0000022726714246	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3900000000000001	0.0000019475000000	0.0000024887848642	0.0000022738670288	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3910000000000000	0.0000019525000000	0.0000024979302701	0.0000022750339097	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3920000000000001	0.0000019575000000	0.0000025070792898	0.0000022761720512	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.3930000000000000	0.0000019625000000	0.0000025162318452	0.0000022772814466	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3940000000000001	0.0000019675000000	0.0000025253878397	0.0000022783620826	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3950000000000000	0.0000019725000000	0.0000025345471846	0.0000022794139491	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3960000000000001	0.0000019775000000	0.0000025437097844	0.0000022804370340	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.3970000000000000	0.0000019825000000	0.0000025528755583	0.0000022814313305	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.3980000000000001	0.0000019875000000	0.0000025620444086	0.0000022823968264	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.3990000000000000	0.0000019925000000	0.0000025712162489	0.0000022833335134	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4000000000000001	0.0000019975000000	0.0000025803909810	0.0000022842413799	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.4010000000000000	0.0000020025000000	0.0000025895685264	0.0000022851204207	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4020000000000001	0.0000020075000000	0.0000025987487813	0.0000022859706229	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4030000000000000	0.0000020125000000	0.0000026079316702	0.0000022867919830	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4040000000000001	0.0000020175000000	0.0000026171170851	0.0000022875844874	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4050000000000000	0.0000020225000000	0.0000026263049553	0.0000022883481344	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4060000000000001	0.0000020275000000	0.0000026354951672	0.0000022890829095	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4070000000000000	0.0000020325000000	0.0000026446876528	0.0000022897888124	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4079999999999999	0.0000020375000000	0.0000026538823066	0.0000022904658315	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4090000000000000	0.0000020425000000	0.0000026630790362	0.0000022911139598	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4099999999999999	0.0000020475000000	0.0000026722777663	0.0000022917331954	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4110000000000000	0.0000020525000000	0.0000026814783887	0.0000022923235271	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4119999999999999	0.0000020575000000	0.0000026906808256	0.0000022928849529	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4130000000000000	0.0000020625000000	0.0000026998849753	0.0000022934174641	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4139999999999999	0.0000020675000000	0.0000027090907579	0.0000022939210585	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4150000000000000	0.0000020725000000	0.0000027182980745	0.0000022943957289	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4159999999999999	0.0000020775000000	0.0000027275068394	0.0000022948414721	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4170000000000000	0.0000020825000000	0.0000027367169533	0.0000022952582813	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4179999999999999	0.0000020875000000	0.0000027459283387	0.0000022956461561	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.4190000000000000	0.0000020925000000	0.0000027551408887	0.0000022960050884	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4199999999999999	0.0000020975000000	0.0000027643545287	0.0000022963350789	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4210000000000000	0.0000021025000000	0.0000027735691549	0.0000022966361210	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4219999999999999	0.0000021075000000	0.0000027827846853	0.0000022969082142	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4230000000000000	0.0000021125000000	0.0000027920010224	0.0000022971513538	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4239999999999999	0.0000021175000000	0.0000028012180820	0.0000022973655394	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4250000000000000	0.0000021225000000	0.0000028104357607	0.0000022975507658	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4259999999999999	0.0000021275000000	0.0000028196539845	0.0000022977070351	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4270000000000000	0.0000021325000000	0.0000028288726459	0.0000022978343420	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4279999999999999	0.0000021375000000	0.0000028380916737	0.0000022979326897	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4290000000000000	0.0000021425000000	0.0000028473109479	0.0000022980020707	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4299999999999999	0.0000021475000000	0.0000028565304090	0.0000022980424915	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4310000000000000	0.0000021525000000	0.0000028657499433	0.0000022980539465	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4319999999999999	0.0000021575000000	0.0000028749694735	0.0000022980364386	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4330000000000001	0.0000021625000000	0.0000028841888992	0.0000022979899660	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4339999999999999	0.0000021675000000	0.0000028934081392	0.0000022979145312	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4350000000000001	0.0000021725000000	0.0000029026270857	0.0000022978101314	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4359999999999999	0.0000021775000000	0.0000029118456708	0.0000022976767726	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4370000000000001	0.0000021825000000	0.0000029210637845	0.0000022975144519	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4379999999999999	0.0000021875000000	0.0000029302813445	0.0000022973231729	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.4390000000000001	0.0000021925000000	0.0000029394982576	0.0000022971029370	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4399999999999999	0.0000021975000000	0.0000029487144358	0.0000022968537469	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4410000000000001	0.0000022025000000	0.0000029579297821	0.0000022965756039	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4419999999999999	0.0000022075000000	0.0000029671442114	0.0000022962685119	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4430000000000001	0.0000022125000000	0.0000029763576278	0.0000022959324730	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4440000000000000	0.0000022175000000	0.0000029855699475	0.0000022955674919	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4450000000000001	0.0000022225000000	0.0000029947810707	0.0000022951735704	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4460000000000000	0.0000022275000000	0.0000030039909148	0.0000022947507140	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4470000000000001	0.0000022325000000	0.0000030131993813	0.0000022942989255	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4480000000000000	0.0000022375000000	0.0000030224063871	0.0000022938182107	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4490000000000001	0.0000022425000000	0.0000030316118297	0.0000022933085724	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4500000000000000	0.0000022475000000	0.0000030408156377	0.0000022927700189	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4510000000000001	0.0000022525000000	0.0000030500176976	0.0000022922025518	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4520000000000000	0.0000022575000000	0.0000030592179358	0.0000022916061794	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4530000000000001	0.0000022625000000	0.0000030684162506	0.0000022909809059	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4540000000000000	0.0000022675000000	0.0000030776125610	0.0000022903267389	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4550000000000001	0.0000022725000000	0.0000030868067628	0.0000022896436830	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4560000000000000	0.0000022775000000	0.0000030959987817	0.0000022889317473	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4570000000000001	0.0000022825000000	0.0000031051885130	0.0000022881909368	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4580000000000000	0.0000022875000000	0.0000031143758783	0.0000022874212605	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4590000000000001	0.0000022925000000	0.0000031235607709	0.0000022866227238	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4600000000000000	0.0000022975000000	0.0000031327431187	0.0000022857953371	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4610000000000001	0.0000023025000000	0.0000031419228110	0.0000022849391060	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4620000000000000	0.0000023075000000	0.0000031510997808	0.0000022840540418	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4630000000000001	0.0000023125000000	0.0000031602739149	0.0000022831401506	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4640000000000000	0.0000023175000000	0.0000031694451387	0.0000022821974433	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4650000000000001	0.0000023225000000	0.0000031786133493	0.0000022812259277	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4660000000000000	0.0000023275000000	0.0000031877784699	0.0000022802256149	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4670000000000001	0.0000023325000000	0.0000031969403969	0.0000022791965135	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.4680000000000000	0.0000023375000000	0.0000032060990513	0.0000022781386347	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4690000000000001	0.0000023425000000	0.0000032152543310	0.0000022770519878	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4700000000000000	0.0000023475000000	0.0000032244061581	0.0000022759365848	0.0031415926535895	0.0000000000000000	0.0000000000000000	
+1.4710000000000001	0.0000023525000000	0.0000032335544300	0.0000022747924355	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4720000000000000	0.0000023575000000	0.0000032426990667	0.0000022736195521	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4730000000000001	0.0000023625000000	0.0000032518399668	0.0000022724179452	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4740000000000000	0.0000023675000000	0.0000032609770535	0.0000022711876279	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4750000000000001	0.0000023725000000	0.0000032701102284	0.0000022699286116	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4760000000000000	0.0000023775000000	0.0000032792394034	0.0000022686409088	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4770000000000001	0.0000023825000000	0.0000032883644853	0.0000022673245321	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4780000000000000	0.0000023875000000	0.0000032974853907	0.0000022659794950	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4790000000000001	0.0000023925000000	0.0000033066020222	0.0000022646058101	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4800000000000000	0.0000023975000000	0.0000033157142963	0.0000022632034916	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.4810000000000001	0.0000024025000000	0.0000033248221149	0.0000022617725526	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4820000000000000	0.0000024075000000	0.0000033339253994	0.0000022603130081	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4830000000000001	0.0000024125000000	0.0000033430240477	0.0000022588248716	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4840000000000000	0.0000024175000000	0.0000033521179825	0.0000022573081587	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4850000000000001	0.0000024225000000	0.0000033612070978	0.0000022557628833	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4860000000000000	0.0000024275000000	0.0000033702913246	0.0000022541890619	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4870000000000001	0.0000024325000000	0.0000033793705529	0.0000022525867088	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4880000000000000	0.0000024375000000	0.0000033884447115	0.0000022509558409	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4890000000000001	0.0000024425000000	0.0000033975136934	0.0000022492964735	0.0031415926535896	0.0000000000000000	0.0000000000000000	
+1.4900000000000000	0.0000024475000000	0.0000034065774236	0.0000022476086235	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4910000000000001	0.0000024525000000	0.0000034156358018	0.0000022458923071	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4920000000000000	0.0000024575000000	0.0000034246887504	0.0000022441475417	0.0031415926535900	0.0000000000000000	0.0000000000000000	
+1.4930000000000001	0.0000024625000000	0.0000034337361636	0.0000022423743441	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4940000000000000	0.0000024675000000	0.0000034427779687	0.0000022405727321	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4950000000000001	0.0000024725000000	0.0000034518140629	0.0000022387427233	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4960000000000000	0.0000024775000000	0.0000034608443713	0.0000022368843359	0.0031415926535899	0.0000000000000000	0.0000000000000000	
+1.4970000000000001	0.0000024825000000	0.0000034698687889	0.0000022349975882	0.0031415926535898	0.0000000000000000	0.0000000000000000	
+1.4980000000000000	0.0000024875000000	0.0000034788872458	0.0000022330824988	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.4990000000000001	0.0000024925000000	0.0000034878996275	0.0000022311390865	0.0031415926535897	0.0000000000000000	0.0000000000000000	
+1.5000000000000000	0.0000024975000000	0.0000034969058707	0.0000022291673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5010000000000001	0.0000025025000000	0.0000034989058665	0.0000022381673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5020000000000000	0.0000025075000000	0.0000035009058695	0.0000022471673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5030000000000001	0.0000025125000000	0.0000035029058653	0.0000022561673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5040000000000000	0.0000025175000000	0.0000035049058682	0.0000022651673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5050000000000001	0.0000025225000000	0.0000035069058658	0.0000022741673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5060000000000000	0.0000025275000000	0.0000035089058705	0.0000022831673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5070000000000001	0.0000025325000000	0.0000035109058645	0.0000022921673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5080000000000000	0.0000025375000000	0.0000035129058692	0.0000023011673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5090000000000001	0.0000025425000000	0.0000035149058668	0.0000023101673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5100000000000000	0.0000025475000000	0.0000035169058697	0.0000023191673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5110000000000001	0.0000025525000000	0.0000035189058655	0.0000023281673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5120000000000000	0.0000025575000000	0.0000035209058684	0.0000023371673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5130000000000001	0.0000025625000000	0.0000035229058660	0.0000023461673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5140000000000000	0.0000025675000000	0.0000035249058689	0.0000023551673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5150000000000001	0.0000025725000000	0.0000035269058665	0.0000023641673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5160000000000000	0.0000025775000000	0.0000035289058694	0.0000023731673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5170000000000001	0.0000025825000000	0.0000035309058634	0.0000023821673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5180000000000000	0.0000025875000000	0.0000035329058699	0.0000023911673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5190000000000001	0.0000025925000000	0.0000035349058693	0.0000024001673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5200000000000000	0.0000025975000000	0.0000035369058669	0.0000024091673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5210000000000001	0.0000026025000000	0.0000035389058644	0.0000024181673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5220000000000000	0.0000026075000000	0.0000035409058691	0.0000024271673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5230000000000001	0.0000026125000000	0.0000035429058649	0.0000024361673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5240000000000000	0.0000026175000000	0.0000035449058696	0.0000024451673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5250000000000001	0.0000026225000000	0.0000035469058654	0.0000024541673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5260000000000000	0.0000026275000000	0.0000035489058701	0.0000024631673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5270000000000001	0.0000026325000000	0.0000035509058659	0.0000024721673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5280000000000000	0.0000026375000000	0.0000035529058706	0.0000024811673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5290000000000001	0.0000026425000000	0.0000035549058647	0.0000024901673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5300000000000000	0.0000026475000000	0.0000035569058693	0.0000024991673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5310000000000001	0.0000026525000000	0.0000035589058652	0.0000025081673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5320000000000000	0.0000026575000000	0.0000035609058681	0.0000025171673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5330000000000001	0.0000026625000000	0.0000035629058657	0.0000025261673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5340000000000000	0.0000026675000000	0.0000035649058703	0.0000025351673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5350000000000001	0.0000026725000000	0.0000035669058679	0.0000025441673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5360000000000000	0.0000026775000000	0.0000035689058691	0.0000025531673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5369999999999999	0.0000026825000000	0.0000035709058684	0.0000025621673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5380000000000000	0.0000026875000000	0.0000035729058660	0.0000025711673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5389999999999999	0.0000026925000000	0.0000035749058672	0.0000025801673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5400000000000000	0.0000026975000000	0.0000035769058665	0.0000025891673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5409999999999999	0.0000027025000000	0.0000035789058677	0.0000025981673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5420000000000000	0.0000027075000000	0.0000035809058670	0.0000026071673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5429999999999999	0.0000027125000000	0.0000035829058681	0.0000026161673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5440000000000000	0.0000027175000000	0.0000035849058657	0.0000026251673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5449999999999999	0.0000027225000000	0.0000035869058704	0.0000026341673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5460000000000000	0.0000027275000000	0.0000035889058680	0.0000026431673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5469999999999999	0.0000027325000000	0.0000035909058674	0.0000026521673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5480000000000000	0.0000027375000000	0.0000035929058650	0.0000026611673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5489999999999999	0.0000027425000000	0.0000035949058696	0.0000026701673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5500000000000000	0.0000027475000000	0.0000035969058637	0.0000026791673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5509999999999999	0.0000027525000000	0.0000035989058701	0.0000026881673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5520000000000000	0.0000027575000000	0.0000036009058660	0.0000026971673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5529999999999999	0.0000027625000000	0.0000036029058706	0.0000027061673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5540000000000000	0.0000027675000000	0.0000036049058647	0.0000027151673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5549999999999999	0.0000027725000000	0.0000036069058729	0.0000027241673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5560000000000000	0.0000027775000000	0.0000036089058634	0.0000027331673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5569999999999999	0.0000027825000000	0.0000036109058699	0.0000027421673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5580000000000001	0.0000027875000000	0.0000036129058639	0.0000027511673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5589999999999999	0.0000027925000000	0.0000036149058686	0.0000027601673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5600000000000001	0.0000027975000000	0.0000036169058662	0.0000027691673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5609999999999999	0.0000028025000000	0.0000036189058691	0.0000027781673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5620000000000001	0.0000028075000000	0.0000036209058667	0.0000027871673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5629999999999999	0.0000028125000000	0.0000036229058696	0.0000027961673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5640000000000001	0.0000028175000000	0.0000036249058672	0.0000028051673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5649999999999999	0.0000028225000000	0.0000036269058683	0.0000028141673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5660000000000001	0.0000028275000000	0.0000036289058659	0.0000028231673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5669999999999999	0.0000028325000000	0.0000036309058670	0.0000028321673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5680000000000001	0.0000028375000000	0.0000036329058664	0.0000028411673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5690000000000000	0.0000028425000000	0.0000036349058693	0.0000028501673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5700000000000001	0.0000028475000000	0.0000036369058669	0.0000028591673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5710000000000000	0.0000028525000000	0.0000036389058680	0.0000028681673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5720000000000001	0.0000028575000000	0.0000036409058674	0.0000028771673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5730000000000000	0.0000028625000000	0.0000036429058685	0.0000028861673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5740000000000001	0.0000028675000000	0.0000036449058661	0.0000028951673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5750000000000000	0.0000028725000000	0.0000036469058690	0.0000029041673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5760000000000001	0.0000028775000000	0.0000036489058648	0.0000029131673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5770000000000000	0.0000028825000000	0.0000036509058695	0.0000029221673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5780000000000001	0.0000028875000000	0.0000036529058636	0.0000029311673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5790000000000000	0.0000028925000000	0.0000036549058718	0.0000029401673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5800000000000001	0.0000028975000000	0.0000036569058641	0.0000029491673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5810000000000000	0.0000029025000000	0.0000036589058705	0.0000029581673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5820000000000001	0.0000029075000000	0.0000036609058681	0.0000029671673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5830000000000000	0.0000029125000000	0.0000036629058675	0.0000029761673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5840000000000001	0.0000029175000000	0.0000036649058651	0.0000029851673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5850000000000000	0.0000029225000000	0.0000036669058697	0.0000029941673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5860000000000001	0.0000029275000000	0.0000036689058638	0.0000030031673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5870000000000000	0.0000029325000000	0.0000036709058702	0.0000030121673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5880000000000001	0.0000029375000000	0.0000036729058661	0.0000030211673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5890000000000000	0.0000029425000000	0.0000036749058690	0.0000030301673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5900000000000001	0.0000029475000000	0.0000036769058666	0.0000030391673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5910000000000000	0.0000029525000000	0.0000036789058712	0.0000030481673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5920000000000001	0.0000029575000000	0.0000036809058635	0.0000030571673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5930000000000000	0.0000029625000000	0.0000036829058682	0.0000030661673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5940000000000001	0.0000029675000000	0.0000036849058676	0.0000030751673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5950000000000000	0.0000029725000000	0.0000036869058687	0.0000030841673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5960000000000001	0.0000029775000000	0.0000036889058663	0.0000030931673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5970000000000000	0.0000029825000000	0.0000036909058692	0.0000031021673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5980000000000001	0.0000029875000000	0.0000036929058650	0.0000031111673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.5990000000000000	0.0000029925000000	0.0000036949058697	0.0000031201673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6000000000000001	0.0000029975000000	0.0000036969058655	0.0000031291673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6010000000000000	0.0000030025000000	0.0000036989058702	0.0000031381673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6020000000000001	0.0000030075000000	0.0000037009058642	0.0000031471673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6030000000000000	0.0000030125000000	0.0000037029058707	0.0000031561673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6040000000000001	0.0000030175000000	0.0000037049058647	0.0000031651673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6050000000000000	0.0000030225000000	0.0000037069058694	0.0000031741673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6060000000000001	0.0000030275000000	0.0000037089058652	0.0000031831673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6070000000000000	0.0000030325000000	0.0000037109058699	0.0000031921673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6080000000000001	0.0000030375000000	0.0000037129058657	0.0000032011673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6090000000000000	0.0000030425000000	0.0000037149058722	0.0000032101673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6100000000000001	0.0000030475000000	0.0000037169058644	0.0000032191673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6110000000000000	0.0000030525000000	0.0000037189058691	0.0000032281673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6120000000000001	0.0000030575000000	0.0000037209058632	0.0000032371673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6130000000000000	0.0000030625000000	0.0000037229058696	0.0000032461673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6140000000000001	0.0000030675000000	0.0000037249058672	0.0000032551673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6150000000000000	0.0000030725000000	0.0000037269058684	0.0000032641673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6160000000000001	0.0000030775000000	0.0000037289058659	0.0000032731673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6170000000000000	0.0000030825000000	0.0000037309058706	0.0000032821673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6180000000000001	0.0000030875000000	0.0000037329058664	0.0000032911673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6190000000000000	0.0000030925000000	0.0000037349058694	0.0000033001673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6200000000000001	0.0000030975000000	0.0000037369058634	0.0000033091673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6210000000000000	0.0000031025000000	0.0000037389058699	0.0000033181673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6220000000000001	0.0000031075000000	0.0000037409058657	0.0000033271673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6230000000000000	0.0000031125000000	0.0000037429058686	0.0000033361673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6240000000000001	0.0000031175000000	0.0000037449058679	0.0000033451673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6250000000000000	0.0000031225000000	0.0000037469058691	0.0000033541673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6260000000000001	0.0000031275000000	0.0000037489058649	0.0000033631673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6270000000000000	0.0000031325000000	0.0000037509058713	0.0000033721673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6280000000000001	0.0000031375000000	0.0000037529058654	0.0000033811673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6290000000000000	0.0000031425000000	0.0000037549058683	0.0000033901673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6300000000000001	0.0000031475000000	0.0000037569058659	0.0000033991673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6310000000000000	0.0000031525000000	0.0000037589058688	0.0000034081673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6320000000000001	0.0000031575000000	0.0000037609058646	0.0000034171673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6330000000000000	0.0000031625000000	0.0000037629058711	0.0000034261673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6340000000000001	0.0000031675000000	0.0000037649058651	0.0000034351673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6350000000000000	0.0000031725000000	0.0000037669058698	0.0000034441673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6360000000000001	0.0000031775000000	0.0000037689058656	0.0000034531673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6370000000000000	0.0000031825000000	0.0000037709058685	0.0000034621673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6380000000000001	0.0000031875000000	0.0000037729058661	0.0000034711673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6390000000000000	0.0000031925000000	0.0000037749058672	0.0000034801673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6400000000000001	0.0000031975000000	0.0000037769058666	0.0000034891673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6410000000000000	0.0000032025000000	0.0000037789058695	0.0000034981673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6420000000000001	0.0000032075000000	0.0000037809058653	0.0000035071673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6430000000000000	0.0000032125000000	0.0000037829058700	0.0000035161673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6440000000000001	0.0000032175000000	0.0000037849058676	0.0000035251673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6450000000000000	0.0000032225000000	0.0000037869058670	0.0000035341673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6460000000000001	0.0000032275000000	0.0000037889058663	0.0000035431673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6470000000000000	0.0000032325000000	0.0000037909058675	0.0000035521673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6480000000000001	0.0000032375000000	0.0000037929058650	0.0000035611673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6490000000000000	0.0000032425000000	0.0000037949058697	0.0000035701673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6500000000000001	0.0000032475000000	0.0000037969058638	0.0000035791673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6510000000000000	0.0000032525000000	0.0000037989058702	0.0000035881673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6520000000000001	0.0000032575000000	0.0000038009058678	0.0000035971673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6530000000000000	0.0000032625000000	0.0000038029058690	0.0000036061673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6540000000000001	0.0000032675000000	0.0000038049058648	0.0000036151673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6550000000000000	0.0000032725000000	0.0000038069058677	0.0000036241673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6560000000000001	0.0000032775000000	0.0000038089058670	0.0000036331673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6570000000000000	0.0000032825000000	0.0000038109058682	0.0000036421673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6580000000000001	0.0000032875000000	0.0000038129058658	0.0000036511673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6590000000000000	0.0000032925000000	0.0000038149058705	0.0000036601673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6600000000000001	0.0000032975000000	0.0000038169058663	0.0000036691673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6610000000000000	0.0000033025000000	0.0000038189058692	0.0000036781673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6620000000000001	0.0000033075000000	0.0000038209058668	0.0000036871673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6630000000000000	0.0000033125000000	0.0000038229058661	0.0000036961673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6640000000000001	0.0000033175000000	0.0000038249058655	0.0000037051673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6650000000000000	0.0000033225000000	0.0000038269058684	0.0000037141673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6659999999999999	0.0000033275000000	0.0000038289058695	0.0000037231673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6670000000000000	0.0000033325000000	0.0000038309058671	0.0000037321673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6679999999999999	0.0000033375000000	0.0000038329058683	0.0000037411673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6690000000000000	0.0000033425000000	0.0000038349058676	0.0000037501673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6699999999999999	0.0000033475000000	0.0000038369058670	0.0000037591673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6710000000000000	0.0000033525000000	0.0000038389058663	0.0000037681673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6719999999999999	0.0000033575000000	0.0000038409058693	0.0000037771673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6730000000000000	0.0000033625000000	0.0000038429058651	0.0000037861673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6739999999999999	0.0000033675000000	0.0000038449058680	0.0000037951673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6750000000000000	0.0000033725000000	0.0000038469058673	0.0000038041673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6759999999999999	0.0000033775000000	0.0000038489058685	0.0000038131673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6770000000000000	0.0000033825000000	0.0000038509058661	0.0000038221673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6779999999999999	0.0000033875000000	0.0000038529058708	0.0000038311673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6790000000000000	0.0000033925000000	0.0000038549058630	0.0000038401673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6799999999999999	0.0000033975000000	0.0000038569058730	0.0000038491673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6810000000000000	0.0000034025000000	0.0000038589058635	0.0000038581673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6819999999999999	0.0000034075000000	0.0000038609058682	0.0000038671673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6830000000000001	0.0000034125000000	0.0000038629058658	0.0000038761673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6839999999999999	0.0000034175000000	0.0000038649058687	0.0000038851673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6850000000000001	0.0000034225000000	0.0000038669058645	0.0000038941673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6859999999999999	0.0000034275000000	0.0000038689058692	0.0000039031673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6870000000000001	0.0000034325000000	0.0000038709058668	0.0000039121673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6879999999999999	0.0000034375000000	0.0000038729058697	0.0000039211673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6890000000000001	0.0000034425000000	0.0000038749058673	0.0000039301673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6899999999999999	0.0000034475000000	0.0000038769058684	0.0000039391673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6910000000000001	0.0000034525000000	0.0000038789058642	0.0000039481673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6919999999999999	0.0000034575000000	0.0000038809058707	0.0000039571673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6930000000000001	0.0000034625000000	0.0000038829058629	0.0000039661673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6940000000000000	0.0000034675000000	0.0000038849058694	0.0000039751673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6950000000000001	0.0000034725000000	0.0000038869058670	0.0000039841673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6960000000000000	0.0000034775000000	0.0000038889058699	0.0000039931673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6970000000000001	0.0000034825000000	0.0000038909058657	0.0000040021673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6980000000000000	0.0000034875000000	0.0000038929058704	0.0000040111673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.6990000000000001	0.0000034925000000	0.0000038949058644	0.0000040201673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7000000000000000	0.0000034975000000	0.0000038969058691	0.0000040291673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7010000000000001	0.0000035025000000	0.0000038989058632	0.0000040381673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7020000000000000	0.0000035075000000	0.0000039009058696	0.0000040471673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7030000000000001	0.0000035125000000	0.0000039029058654	0.0000040561673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7040000000000000	0.0000035175000000	0.0000039049058701	0.0000040651673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7050000000000001	0.0000035225000000	0.0000039069058659	0.0000040741673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7060000000000000	0.0000035275000000	0.0000039089058706	0.0000040831673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7070000000000001	0.0000035325000000	0.0000039109058647	0.0000040921673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7080000000000000	0.0000035375000000	0.0000039129058694	0.0000041011673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7090000000000001	0.0000035425000000	0.0000039149058669	0.0000041101673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7100000000000000	0.0000035475000000	0.0000039169058681	0.0000041191673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7110000000000001	0.0000035525000000	0.0000039189058657	0.0000041281673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7120000000000000	0.0000035575000000	0.0000039209058686	0.0000041371673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7130000000000001	0.0000035625000000	0.0000039229058662	0.0000041461673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7140000000000000	0.0000035675000000	0.0000039249058673	0.0000041551673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7150000000000001	0.0000035725000000	0.0000039269058684	0.0000041641673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7160000000000000	0.0000035775000000	0.0000039289058696	0.0000041731673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7170000000000001	0.0000035825000000	0.0000039309058636	0.0000041821673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7180000000000000	0.0000035875000000	0.0000039329058683	0.0000041911673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7190000000000001	0.0000035925000000	0.0000039349058659	0.0000042001673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7200000000000000	0.0000035975000000	0.0000039369058706	0.0000042091673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7210000000000001	0.0000036025000000	0.0000039389058646	0.0000042181673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7220000000000000	0.0000036075000000	0.0000039409058693	0.0000042271673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7230000000000001	0.0000036125000000	0.0000039429058669	0.0000042361673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7240000000000000	0.0000036175000000	0.0000039449058698	0.0000042451673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7250000000000001	0.0000036225000000	0.0000039469058656	0.0000042541673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7260000000000000	0.0000036275000000	0.0000039489058685	0.0000042631673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7270000000000001	0.0000036325000000	0.0000039509058643	0.0000042721673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7280000000000000	0.0000036375000000	0.0000039529058708	0.0000042811673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7290000000000001	0.0000036425000000	0.0000039549058648	0.0000042901673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7300000000000000	0.0000036475000000	0.0000039569058677	0.0000042991673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7310000000000001	0.0000036525000000	0.0000039589058671	0.0000043081673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7320000000000000	0.0000036575000000	0.0000039609058700	0.0000043171673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7330000000000001	0.0000036625000000	0.0000039629058641	0.0000043261673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7340000000000000	0.0000036675000000	0.0000039649058723	0.0000043351673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7350000000000001	0.0000036725000000	0.0000039669058645	0.0000043441673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7360000000000000	0.0000036775000000	0.0000039689058692	0.0000043531673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7370000000000001	0.0000036825000000	0.0000039709058633	0.0000043621673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7380000000000000	0.0000036875000000	0.0000039729058697	0.0000043711673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7390000000000001	0.0000036925000000	0.0000039749058655	0.0000043801673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7400000000000000	0.0000036975000000	0.0000039769058702	0.0000043891673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7410000000000001	0.0000037025000000	0.0000039789058660	0.0000043981673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7420000000000000	0.0000037075000000	0.0000039809058690	0.0000044071673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7430000000000001	0.0000037125000000	0.0000039829058665	0.0000044161673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7440000000000000	0.0000037175000000	0.0000039849058695	0.0000044251673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7450000000000001	0.0000037225000000	0.0000039869058653	0.0000044341673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7460000000000000	0.0000037275000000	0.0000039889058700	0.0000044431673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7470000000000001	0.0000037325000000	0.0000039909058640	0.0000044521673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7480000000000000	0.0000037375000000	0.0000039929058687	0.0000044611673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7490000000000001	0.0000037425000000	0.0000039949058663	0.0000044701673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7500000000000000	0.0000037475000000	0.0000039969058692	0.0000044791673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7510000000000001	0.0000037525000000	0.0000039989058668	0.0000044881673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7520000000000000	0.0000037575000000	0.0000040009058715	0.0000044971673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7530000000000001	0.0000037625000000	0.0000040029058637	0.0000045061673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7540000000000000	0.0000037675000000	0.0000040049058684	0.0000045151673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7550000000000001	0.0000037725000000	0.0000040069058642	0.0000045241673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7560000000000000	0.0000037775000000	0.0000040089058707	0.0000045331673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7570000000000001	0.0000037825000000	0.0000040109058647	0.0000045421673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7580000000000000	0.0000037875000000	0.0000040129058694	0.0000045511673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7590000000000001	0.0000037925000000	0.0000040149058652	0.0000045601673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7600000000000000	0.0000037975000000	0.0000040169058717	0.0000045691673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7610000000000001	0.0000038025000000	0.0000040189058639	0.0000045781673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7620000000000000	0.0000038075000000	0.0000040209058686	0.0000045871673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7630000000000001	0.0000038125000000	0.0000040229058644	0.0000045961673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7640000000000000	0.0000038175000000	0.0000040249058691	0.0000046051673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7650000000000001	0.0000038225000000	0.0000040269058649	0.0000046141673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7660000000000000	0.0000038275000000	0.0000040289058714	0.0000046231673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7670000000000001	0.0000038325000000	0.0000040309058654	0.0000046321673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7680000000000000	0.0000038375000000	0.0000040329058683	0.0000046411673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7690000000000001	0.0000038425000000	0.0000040349058677	0.0000046501673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7700000000000000	0.0000038475000000	0.0000040369058671	0.0000046591673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7710000000000001	0.0000038525000000	0.0000040389058647	0.0000046681673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7720000000000000	0.0000038575000000	0.0000040409058693	0.0000046771673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7730000000000001	0.0000038625000000	0.0000040429058652	0.0000046861673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7740000000000000	0.0000038675000000	0.0000040449058681	0.0000046951673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7750000000000001	0.0000038725000000	0.0000040469058656	0.0000047041673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7760000000000000	0.0000038775000000	0.0000040489058703	0.0000047131673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7770000000000001	0.0000038825000000	0.0000040509058661	0.0000047221673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7780000000000000	0.0000038875000000	0.0000040529058691	0.0000047311673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7790000000000001	0.0000038925000000	0.0000040549058649	0.0000047401673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7800000000000000	0.0000038975000000	0.0000040569058696	0.0000047491673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7810000000000001	0.0000039025000000	0.0000040589058654	0.0000047581673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7820000000000000	0.0000039075000000	0.0000040609058683	0.0000047671673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7830000000000001	0.0000039125000000	0.0000040629058641	0.0000047761673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7840000000000000	0.0000039175000000	0.0000040649058706	0.0000047851673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7850000000000001	0.0000039225000000	0.0000040669058664	0.0000047941673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7860000000000000	0.0000039275000000	0.0000040689058693	0.0000048031673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7870000000000001	0.0000039325000000	0.0000040709058669	0.0000048121673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7880000000000000	0.0000039375000000	0.0000040729058680	0.0000048211673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7890000000000001	0.0000039425000000	0.0000040749058638	0.0000048301673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7900000000000000	0.0000039475000000	0.0000040769058703	0.0000048391673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7910000000000001	0.0000039525000000	0.0000040789058643	0.0000048481673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7920000000000000	0.0000039575000000	0.0000040809058690	0.0000048571673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7929999999999999	0.0000039625000000	0.0000040829058701	0.0000048661673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7940000000000000	0.0000039675000000	0.0000040849058660	0.0000048751673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7949999999999999	0.0000039725000000	0.0000040869058689	0.0000048841673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7960000000000000	0.0000039775000000	0.0000040889058664	0.0000048931673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7969999999999999	0.0000039825000000	0.0000040909058694	0.0000049021673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7980000000000000	0.0000039875000000	0.0000040929058634	0.0000049111673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.7989999999999999	0.0000039925000000	0.0000040949058699	0.0000049201673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8000000000000000	0.0000039975000000	0.0000040969058639	0.0000049291673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8009999999999999	0.0000040025000000	0.0000040989058686	0.0000049381673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8020000000000000	0.0000040075000000	0.0000041009058679	0.0000049471673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8029999999999999	0.0000040125000000	0.0000041029058691	0.0000049561673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8040000000000000	0.0000040175000000	0.0000041049058667	0.0000049651673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8049999999999999	0.0000040225000000	0.0000041069058678	0.0000049741673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8060000000000000	0.0000040275000000	0.0000041089058654	0.0000049831673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8069999999999999	0.0000040325000000	0.0000041109058719	0.0000049921673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8080000000000001	0.0000040375000000	0.0000041129058677	0.0000050011673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8089999999999999	0.0000040425000000	0.0000041149058724	0.0000050101673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8100000000000001	0.0000040475000000	0.0000041169058699	0.0000050191673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8109999999999999	0.0000040525000000	0.0000041189058711	0.0000050281673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8120000000000001	0.0000040575000000	0.0000041209058651	0.0000050371673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8129999999999999	0.0000040625000000	0.0000041229058734	0.0000050461673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8140000000000001	0.0000040675000000	0.0000041249058638	0.0000050551673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8149999999999999	0.0000040725000000	0.0000041269058721	0.0000050641673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8160000000000001	0.0000040775000000	0.0000041289058661	0.0000050731673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8169999999999999	0.0000040825000000	0.0000041309058744	0.0000050821673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8180000000000001	0.0000040875000000	0.0000041329058648	0.0000050911673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8190000000000000	0.0000040925000000	0.0000041349058766	0.0000051001673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8200000000000001	0.0000040975000000	0.0000041369058636	0.0000051091673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8210000000000000	0.0000041025000000	0.0000041389058718	0.0000051181673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8220000000000001	0.0000041075000000	0.0000041409058694	0.0000051271673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8230000000000000	0.0000041125000000	0.0000041429058670	0.0000051361673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8240000000000001	0.0000041175000000	0.0000041449058681	0.0000051451673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8250000000000000	0.0000041225000000	0.0000041469058692	0.0000051541673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8260000000000001	0.0000041275000000	0.0000041489058704	0.0000051631673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8270000000000000	0.0000041325000000	0.0000041509058715	0.0000051721673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8280000000000001	0.0000041375000000	0.0000041529058656	0.0000051811673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8290000000000000	0.0000041425000000	0.0000041549058702	0.0000051901673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8300000000000001	0.0000041475000000	0.0000041569058643	0.0000051991673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8310000000000000	0.0000041525000000	0.0000041589058761	0.0000052081673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8320000000000001	0.0000041575000000	0.0000041609058630	0.0000052171673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8330000000000000	0.0000041625000000	0.0000041629058712	0.0000052261673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8340000000000001	0.0000041675000000	0.0000041649058688	0.0000052351673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8350000000000000	0.0000041725000000	0.0000041669058700	0.0000052441673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8360000000000001	0.0000041775000000	0.0000041689058711	0.0000052531673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8370000000000000	0.0000041825000000	0.0000041709058687	0.0000052621673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8380000000000001	0.0000041875000000	0.0000041729058663	0.0000052711673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8390000000000000	0.0000041925000000	0.0000041749058710	0.0000052801673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8400000000000001	0.0000041975000000	0.0000041769058650	0.0000052891673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8410000000000000	0.0000042025000000	0.0000041789058697	0.0000052981673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8420000000000001	0.0000042075000000	0.0000041809058708	0.0000053071673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8430000000000000	0.0000042125000000	0.0000041829058684	0.0000053161673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8440000000000001	0.0000042175000000	0.0000041849058695	0.0000053251673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8450000000000000	0.0000042225000000	0.0000041869058707	0.0000053341673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8460000000000001	0.0000042275000000	0.0000041889058647	0.0000053431673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8470000000000000	0.0000042325000000	0.0000041909058730	0.0000053521673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8480000000000001	0.0000042375000000	0.0000041929058634	0.0000053611673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8490000000000000	0.0000042425000000	0.0000041949058752	0.0000053701673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8500000000000001	0.0000042475000000	0.0000041969058622	0.0000053791673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8510000000000000	0.0000042525000000	0.0000041989058740	0.0000053881673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8520000000000001	0.0000042575000000	0.0000042009058644	0.0000053971673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8530000000000000	0.0000042625000000	0.0000042029058727	0.0000054061673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8540000000000001	0.0000042675000000	0.0000042049058667	0.0000054151673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8550000000000000	0.0000042725000000	0.0000042069058714	0.0000054241673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8560000000000001	0.0000042775000000	0.0000042089058690	0.0000054331673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8570000000000000	0.0000042825000000	0.0000042109058666	0.0000054421673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8580000000000001	0.0000042875000000	0.0000042129058713	0.0000054511673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8590000000000000	0.0000042925000000	0.0000042149058688	0.0000054601673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8600000000000001	0.0000042975000000	0.0000042169058664	0.0000054691673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8610000000000000	0.0000043025000000	0.0000042189058711	0.0000054781673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8620000000000001	0.0000043075000000	0.0000042209058687	0.0000054871673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8630000000000000	0.0000043125000000	0.0000042229058734	0.0000054961673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8640000000000001	0.0000043175000000	0.0000042249058639	0.0000055051673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8650000000000000	0.0000043225000000	0.0000042269058686	0.0000055141673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8660000000000001	0.0000043275000000	0.0000042289058697	0.0000055231673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8670000000000000	0.0000043325000000	0.0000042309058708	0.0000055321673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8680000000000001	0.0000043375000000	0.0000042329058649	0.0000055411673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8690000000000000	0.0000043425000000	0.0000042349058696	0.0000055501673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8700000000000001	0.0000043475000000	0.0000042369058672	0.0000055591673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8710000000000000	0.0000043525000000	0.0000042389058754	0.0000055681673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8720000000000001	0.0000043575000000	0.0000042409058659	0.0000055771673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8730000000000000	0.0000043625000000	0.0000042429058706	0.0000055861673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8740000000000001	0.0000043675000000	0.0000042449058646	0.0000055951673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8750000000000000	0.0000043725000000	0.0000042469058728	0.0000056041673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8760000000000001	0.0000043775000000	0.0000042489058669	0.0000056131673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8770000000000000	0.0000043825000000	0.0000042509058716	0.0000056221673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8780000000000001	0.0000043875000000	0.0000042529058656	0.0000056311673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8790000000000000	0.0000043925000000	0.0000042549058703	0.0000056401673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8800000000000001	0.0000043975000000	0.0000042569058679	0.0000056491673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8810000000000000	0.0000044025000000	0.0000042589058726	0.0000056581673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8820000000000001	0.0000044075000000	0.0000042609058666	0.0000056671673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8830000000000000	0.0000044125000000	0.0000042629058713	0.0000056761673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8840000000000001	0.0000044175000000	0.0000042649058653	0.0000056851673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8850000000000000	0.0000044225000000	0.0000042669058736	0.0000056941673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8860000000000001	0.0000044275000000	0.0000042689058640	0.0000057031673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8870000000000000	0.0000044325000000	0.0000042709058723	0.0000057121673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8880000000000001	0.0000044375000000	0.0000042729058663	0.0000057211673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8890000000000000	0.0000044425000000	0.0000042749058710	0.0000057301673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8900000000000001	0.0000044475000000	0.0000042769058686	0.0000057391673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8910000000000000	0.0000044525000000	0.0000042789058697	0.0000057481673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8920000000000001	0.0000044575000000	0.0000042809058673	0.0000057571673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8930000000000000	0.0000044625000000	0.0000042829058685	0.0000057661673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8940000000000001	0.0000044675000000	0.0000042849058696	0.0000057751673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8950000000000000	0.0000044725000000	0.0000042869058672	0.0000057841673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8960000000000001	0.0000044775000000	0.0000042889058683	0.0000057931673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8970000000000000	0.0000044825000000	0.0000042909058730	0.0000058021673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8980000000000001	0.0000044875000000	0.0000042929058670	0.0000058111673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.8990000000000000	0.0000044925000000	0.0000042949058717	0.0000058201673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9000000000000001	0.0000044975000000	0.0000042969058658	0.0000058291673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9010000000000000	0.0000045025000000	0.0000042989058704	0.0000058381673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9020000000000001	0.0000045075000000	0.0000043009058680	0.0000058471673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9030000000000000	0.0000045125000000	0.0000043029058727	0.0000058561673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9040000000000001	0.0000045175000000	0.0000043049058632	0.0000058651673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9050000000000000	0.0000045225000000	0.0000043069058750	0.0000058741673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9060000000000001	0.0000045275000000	0.0000043089058655	0.0000058831673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9070000000000000	0.0000045325000000	0.0000043109058702	0.0000058921673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9080000000000001	0.0000045375000000	0.0000043129058678	0.0000059011673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9090000000000000	0.0000045425000000	0.0000043149058689	0.0000059101673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9100000000000001	0.0000045475000000	0.0000043169058700	0.0000059191673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9110000000000000	0.0000045525000000	0.0000043189058676	0.0000059281673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9120000000000001	0.0000045575000000	0.0000043209058688	0.0000059371673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9130000000000000	0.0000045625000000	0.0000043229058699	0.0000059461673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9140000000000001	0.0000045675000000	0.0000043249058675	0.0000059551673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9150000000000000	0.0000045725000000	0.0000043269058722	0.0000059641673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9160000000000001	0.0000045775000000	0.0000043289058662	0.0000059731673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9170000000000000	0.0000045825000000	0.0000043309058709	0.0000059821673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9180000000000001	0.0000045875000000	0.0000043329058649	0.0000059911673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9190000000000000	0.0000045925000000	0.0000043349058732	0.0000060001673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9199999999999999	0.0000045975000000	0.0000043369058707	0.0000060091673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9210000000000000	0.0000046025000000	0.0000043389058648	0.0000060181673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9219999999999999	0.0000046075000000	0.0000043409058730	0.0000060271673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9230000000000000	0.0000046125000000	0.0000043429058671	0.0000060361673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9239999999999999	0.0000046175000000	0.0000043449058717	0.0000060451673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9250000000000000	0.0000046225000000	0.0000043469058658	0.0000060541673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9259999999999999	0.0000046275000000	0.0000043489058740	0.0000060631673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9270000000000000	0.0000046325000000	0.0000043509058645	0.0000060721673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9279999999999999	0.0000046375000000	0.0000043529058727	0.0000060811673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9290000000000000	0.0000046425000000	0.0000043549058668	0.0000060901673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9299999999999999	0.0000046475000000	0.0000043569058679	0.0000060991673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9310000000000000	0.0000046525000000	0.0000043589058691	0.0000061081673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9319999999999999	0.0000046575000000	0.0000043609058702	0.0000061171673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9330000000000001	0.0000046625000000	0.0000043629058678	0.0000061261673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9339999999999999	0.0000046675000000	0.0000043649058725	0.0000061351673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9350000000000001	0.0000046725000000	0.0000043669058665	0.0000061441673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9359999999999999	0.0000046775000000	0.0000043689058712	0.0000061531673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9370000000000001	0.0000046825000000	0.0000043709058652	0.0000061621673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9379999999999999	0.0000046875000000	0.0000043729058699	0.0000061711673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9390000000000001	0.0000046925000000	0.0000043749058675	0.0000061801673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9399999999999999	0.0000046975000000	0.0000043769058722	0.0000061891673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9410000000000001	0.0000047025000000	0.0000043789058698	0.0000061981673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9419999999999999	0.0000047075000000	0.0000043809058674	0.0000062071673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9430000000000001	0.0000047125000000	0.0000043829058685	0.0000062161673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9440000000000000	0.0000047175000000	0.0000043849058732	0.0000062251673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9450000000000001	0.0000047225000000	0.0000043869058637	0.0000062341673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9460000000000000	0.0000047275000000	0.0000043889058719	0.0000062431673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9470000000000001	0.0000047325000000	0.0000043909058659	0.0000062521673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9480000000000000	0.0000047375000000	0.0000043929058706	0.0000062611673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9490000000000001	0.0000047425000000	0.0000043949058682	0.0000062701673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9500000000000000	0.0000047475000000	0.0000043969058729	0.0000062791673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9510000000000001	0.0000047525000000	0.0000043989058669	0.0000062881673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9520000000000000	0.0000047575000000	0.0000044009058716	0.0000062971673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9530000000000001	0.0000047625000000	0.0000044029058657	0.0000063061673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9540000000000000	0.0000047675000000	0.0000044049058704	0.0000063151673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9550000000000001	0.0000047725000000	0.0000044069058679	0.0000063241673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9560000000000000	0.0000047775000000	0.0000044089058691	0.0000063331673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9570000000000001	0.0000047825000000	0.0000044109058667	0.0000063421673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9580000000000000	0.0000047875000000	0.0000044129058713	0.0000063511673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9590000000000001	0.0000047925000000	0.0000044149058689	0.0000063601673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9600000000000000	0.0000047975000000	0.0000044169058701	0.0000063691673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9610000000000001	0.0000048025000000	0.0000044189058677	0.0000063781673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9620000000000000	0.0000048075000000	0.0000044209058723	0.0000063871673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9630000000000001	0.0000048125000000	0.0000044229058664	0.0000063961673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9640000000000000	0.0000048175000000	0.0000044249058711	0.0000064051673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9650000000000001	0.0000048225000000	0.0000044269058651	0.0000064141673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9660000000000000	0.0000048275000000	0.0000044289058733	0.0000064231673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9670000000000001	0.0000048325000000	0.0000044309058638	0.0000064321673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9680000000000000	0.0000048375000000	0.0000044329058721	0.0000064411673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9690000000000001	0.0000048425000000	0.0000044349058661	0.0000064501673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9700000000000000	0.0000048475000000	0.0000044369058743	0.0000064591673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9710000000000001	0.0000048525000000	0.0000044389058684	0.0000064681673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9720000000000000	0.0000048575000000	0.0000044409058695	0.0000064771673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9730000000000001	0.0000048625000000	0.0000044429058635	0.0000064861673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9740000000000000	0.0000048675000000	0.0000044449058718	0.0000064951673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9750000000000001	0.0000048725000000	0.0000044469058694	0.0000065041673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9760000000000000	0.0000048775000000	0.0000044489058670	0.0000065131673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9770000000000001	0.0000048825000000	0.0000044509058717	0.0000065221673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9780000000000000	0.0000048875000000	0.0000044529058692	0.0000065311673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9790000000000001	0.0000048925000000	0.0000044549058704	0.0000065401673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9800000000000000	0.0000048975000000	0.0000044569058680	0.0000065491673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9810000000000001	0.0000049025000000	0.0000044589058691	0.0000065581673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9820000000000000	0.0000049075000000	0.0000044609058702	0.0000065671673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9830000000000001	0.0000049125000000	0.0000044629058643	0.0000065761673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9840000000000000	0.0000049175000000	0.0000044649058725	0.0000065851673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9850000000000001	0.0000049225000000	0.0000044669058665	0.0000065941673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9860000000000000	0.0000049275000000	0.0000044689058712	0.0000066031673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9870000000000001	0.0000049325000000	0.0000044709058653	0.0000066121673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9880000000000000	0.0000049375000000	0.0000044729058735	0.0000066211673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9890000000000001	0.0000049425000000	0.0000044749058675	0.0000066301673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9900000000000000	0.0000049475000000	0.0000044769058687	0.0000066391673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9910000000000001	0.0000049525000000	0.0000044789058663	0.0000066481673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9920000000000000	0.0000049575000000	0.0000044809058710	0.0000066571673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9930000000000001	0.0000049625000000	0.0000044829058685	0.0000066661673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9940000000000000	0.0000049675000000	0.0000044849058697	0.0000066751673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9950000000000001	0.0000049725000000	0.0000044869058708	0.0000066841673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9960000000000000	0.0000049775000000	0.0000044889058684	0.0000066931673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9970000000000001	0.0000049825000000	0.0000044909058695	0.0000067021673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9980000000000000	0.0000049875000000	0.0000044929058707	0.0000067111673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+1.9990000000000001	0.0000049925000000	0.0000044949058647	0.0000067201673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+2.0000000000000000	0.0000049975000000	0.0000044969058729	0.0000067291673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+2.0009999999999999	0.0000050025000000	0.0000044989058705	0.0000067381673707	0.0000000000000000	0.0000000000000000	0.0000000000000000	
+2.0020000000000002	0.0000050075000000	0.0000045009058646	0.0000067471673707	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0030000000000001	0.0000049912643229	0.0000045029058656	0.0000067718734059	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0040000000000000	0.0000049749511098	0.0000045049058771	0.0000067965283134	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0049999999999999	0.0000049585605217	0.0000045069058675	0.0000068211318498	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0060000000000002	0.0000049420927202	0.0000045089058655	0.0000068456837723	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0070000000000001	0.0000049255478681	0.0000045109058713	0.0000068701838386	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0080000000000000	0.0000049089261284	0.0000045129058710	0.0000068946318070	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0089999999999999	0.0000048922276654	0.0000045149058719	0.0000069190274360	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0100000000000002	0.0000048754526437	0.0000045169058602	0.0000069433704850	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0110000000000001	0.0000048586012290	0.0000045189058717	0.0000069676607136	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0120000000000000	0.0000048416735876	0.0000045209058710	0.0000069918978822	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0129999999999999	0.0000048246698866	0.0000045229058727	0.0000070160817515	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0140000000000002	0.0000048075902937	0.0000045249058629	0.0000070402120829	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0150000000000001	0.0000047904349776	0.0000045269058666	0.0000070642886381	-0.0000000000000002	0.0031415926535898	-0.0000000000000000	
+2.0160000000000000	0.0000047732041075	0.0000045289058735	0.0000070883111796	0.0000000000000002	0.0031415926535898	-0.0000000000000000	
+2.0169999999999999	0.0000047558978535	0.0000045309058661	0.0000071122794703	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0180000000000002	0.0000047385163864	0.0000045329058660	0.0000071361932736	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0190000000000001	0.0000047210598779	0.0000045349058735	0.0000071600523535	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0200000000000000	0.0000047035285000	0.0000045369058675	0.0000071838564744	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0209999999999999	0.0000046859224260	0.0000045389058696	0.0000072076054016	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0220000000000002	0.0000046682418295	0.0000045409058623	0.0000072312989005	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0230000000000001	0.0000046504868850	0.0000045429058672	0.0000072549367374	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0240000000000000	0.0000046326577679	0.0000045449058740	0.0000072785186789	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0249999999999999	0.0000046147546540	0.0000045469058650	0.0000073020444923	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0260000000000002	0.0000045967777200	0.0000045489058619	0.0000073255139454	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0270000000000001	0.0000045787271434	0.0000045509058721	0.0000073489268066	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0280000000000000	0.0000045606031024	0.0000045529058674	0.0000073722828448	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0289999999999999	0.0000045424057757	0.0000045549058694	0.0000073955818295	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0300000000000002	0.0000045241353430	0.0000045569058641	0.0000074188235307	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0310000000000001	0.0000045057919847	0.0000045589058696	0.0000074420077190	0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0320000000000000	0.0000044873758817	0.0000045609058684	0.0000074651341657	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0329999999999999	0.0000044688872159	0.0000045629058678	0.0000074882026424	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0340000000000003	0.0000044503261696	0.0000045649058646	0.0000075112129216	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0350000000000001	0.0000044316929262	0.0000045669058732	0.0000075341647760	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0360000000000000	0.0000044129876694	0.0000045689058690	0.0000075570579792	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0369999999999999	0.0000043942105839	0.0000045709058666	0.0000075798923053	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0380000000000003	0.0000043753618551	0.0000045729058660	0.0000076026675288	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0390000000000001	0.0000043564416689	0.0000045749058642	0.0000076253834250	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0400000000000000	0.0000043374502121	0.0000045769058719	0.0000076480397697	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0409999999999999	0.0000043183876722	0.0000045789058753	0.0000076706363392	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0420000000000003	0.0000042992542372	0.0000045809058603	0.0000076931729105	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0430000000000001	0.0000042800500960	0.0000045829058699	0.0000077156492614	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0440000000000000	0.0000042607754382	0.0000045849058687	0.0000077380651698	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0449999999999999	0.0000042414304539	0.0000045869058749	0.0000077604204146	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0460000000000003	0.0000042220153342	0.0000045889058567	0.0000077827147750	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0470000000000002	0.0000042025302706	0.0000045909058712	0.0000078049480312	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0480000000000000	0.0000041829754554	0.0000045929058725	0.0000078271199637	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0489999999999999	0.0000041633510816	0.0000045949058678	0.0000078492303535	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0499999999999998	0.0000041436573430	0.0000045969058682	0.0000078712789826	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0510000000000002	0.0000041238944339	0.0000045989058633	0.0000078932656332	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0520000000000000	0.0000041040625493	0.0000046009058745	0.0000079151900885	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0529999999999999	0.0000040841618849	0.0000046029058702	0.0000079370521319	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0539999999999998	0.0000040641926373	0.0000046049058684	0.0000079588515478	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0550000000000002	0.0000040441550034	0.0000046069058587	0.0000079805881209	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0560000000000000	0.0000040240491811	0.0000046089058733	0.0000080022616369	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0569999999999999	0.0000040038753687	0.0000046109058663	0.0000080238718816	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0579999999999998	0.0000039836337654	0.0000046129058663	0.0000080454186419	0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0590000000000002	0.0000039633245710	0.0000046149058629	0.0000080669017052	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0600000000000001	0.0000039429479859	0.0000046169058707	0.0000080883208593	-0.0000000000000002	0.0031415926535898	-0.0000000000000000	
+2.0609999999999999	0.0000039225042111	0.0000046189058684	0.0000081096758929	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0619999999999998	0.0000039019934486	0.0000046209058706	0.0000081309665952	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0630000000000002	0.0000038814159006	0.0000046229058634	0.0000081521927560	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0640000000000001	0.0000038607717704	0.0000046249058717	0.0000081733541660	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0649999999999999	0.0000038400612616	0.0000046269058640	0.0000081944506162	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0659999999999998	0.0000038192845787	0.0000046289058723	0.0000082154818984	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0670000000000002	0.0000037984419267	0.0000046309058580	0.0000082364478050	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0680000000000001	0.0000037775335113	0.0000046329058709	0.0000082573481292	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0690000000000000	0.0000037565595389	0.0000046349058722	0.0000082781826646	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0699999999999998	0.0000037355202165	0.0000046369058728	0.0000082989512057	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0710000000000002	0.0000037144157518	0.0000046389058588	0.0000083196535473	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0720000000000001	0.0000036932463529	0.0000046409058766	0.0000083402894854	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0730000000000000	0.0000036720122289	0.0000046429058695	0.0000083608588160	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0739999999999998	0.0000036507135894	0.0000046449058698	0.0000083813613363	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0750000000000002	0.0000036293506445	0.0000046469058599	0.0000084017968438	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0760000000000001	0.0000036079236051	0.0000046489058721	0.0000084221651370	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0770000000000000	0.0000035864326826	0.0000046509058675	0.0000084424660147	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0779999999999998	0.0000035648780892	0.0000046529058748	0.0000084626992767	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0790000000000002	0.0000035432600377	0.0000046549058587	0.0000084828647231	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0800000000000001	0.0000035215787412	0.0000046569058727	0.0000085029621550	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0810000000000000	0.0000034998344140	0.0000046589058709	0.0000085229913741	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0819999999999999	0.0000034780272705	0.0000046609058676	0.0000085429521826	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0830000000000002	0.0000034561575260	0.0000046629058632	0.0000085628443835	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0840000000000001	0.0000034342253963	0.0000046649058685	0.0000085826677806	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0850000000000000	0.0000034122310979	0.0000046669058696	0.0000086024221782	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0859999999999999	0.0000033901748479	0.0000046689058702	0.0000086221073813	0.0000000000000002	0.0031415926535897	0.0000000000000000	
+2.0870000000000002	0.0000033680568639	0.0000046709058599	0.0000086417231955	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0880000000000001	0.0000033458773643	0.0000046729058708	0.0000086612694274	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.0890000000000000	0.0000033236365680	0.0000046749058678	0.0000086807458840	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0899999999999999	0.0000033013346944	0.0000046769058688	0.0000087001523731	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0910000000000002	0.0000032789719637	0.0000046789058598	0.0000087194887031	0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.0920000000000001	0.0000032565485965	0.0000046809058729	0.0000087387546833	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.0930000000000000	0.0000032340648143	0.0000046829058695	0.0000087579501234	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0939999999999999	0.0000032115208388	0.0000046849058709	0.0000087770748340	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.0950000000000002	0.0000031889168927	0.0000046869058597	0.0000087961286263	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0960000000000001	0.0000031662531989	0.0000046889058680	0.0000088151113124	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.0970000000000000	0.0000031435299812	0.0000046909058712	0.0000088340227048	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.0979999999999999	0.0000031207474639	0.0000046929058661	0.0000088528626169	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.0990000000000002	0.0000030979058717	0.0000046949058633	0.0000088716308627	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1000000000000001	0.0000030750054302	0.0000046969058739	0.0000088903272571	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1010000000000000	0.0000030520463653	0.0000046989058661	0.0000089089516154	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1019999999999999	0.0000030290289037	0.0000047009058684	0.0000089275037540	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1030000000000002	0.0000030059532725	0.0000047029058670	0.0000089459834896	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1040000000000001	0.0000029828196995	0.0000047049058656	0.0000089643906400	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.1050000000000000	0.0000029596284129	0.0000047069058715	0.0000089827250233	-0.0000000000000001	0.0031415926535897	-0.0000000000000000	
+2.1059999999999999	0.0000029363796418	0.0000047089058708	0.0000090009864587	-0.0000000000000002	0.0031415926535899	-0.0000000000000000	
+2.1070000000000002	0.0000029130736154	0.0000047109058635	0.0000090191747659	-0.0000000000000002	0.0031415926535898	-0.0000000000000000	
+2.1080000000000001	0.0000028897105639	0.0000047129058678	0.0000090372897655	0.0000000000000000	0.0031415926535897	-0.0000000000000000	
+2.1090000000000000	0.0000028662907179	0.0000047149058696	0.0000090553312786	-0.0000000000000002	0.0031415926535898	-0.0000000000000000	
+2.1099999999999999	0.0000028428143084	0.0000047169058691	0.0000090732991272	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.1110000000000002	0.0000028192815672	0.0000047189058630	0.0000090911931339	-0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1120000000000001	0.0000027956927266	0.0000047209058728	0.0000091090131222	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1130000000000000	0.0000027720480193	0.0000047229058738	0.0000091267589161	0.0000000000000002	0.0031415926535898	0.0000000000000000	
+2.1139999999999999	0.0000027483476787	0.0000047249058663	0.0000091444303405	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.1150000000000002	0.0000027245919388	0.0000047269058647	0.0000091620272210	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1160000000000001	0.0000027007810339	0.0000047289058692	0.0000091795493840	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1170000000000000	0.0000026769151992	0.0000047309058694	0.0000091969966564	-0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.1179999999999999	0.0000026529946700	0.0000047329058654	0.0000092143688661	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1190000000000002	0.0000026290196826	0.0000047349058645	0.0000092316658417	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.1200000000000001	0.0000026049904736	0.0000047369058670	0.0000092488874124	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1210000000000000	0.0000025809072800	0.0000047389058766	0.0000092660334083	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1219999999999999	0.0000025567703397	0.0000047409058687	0.0000092831036600	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1230000000000002	0.0000025325798908	0.0000047429058612	0.0000093000979992	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1240000000000001	0.0000025083361721	0.0000047449058686	0.0000093170162582	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1250000000000000	0.0000024840394228	0.0000047469058696	0.0000093338582699	-0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1259999999999999	0.0000024596898827	0.0000047489058717	0.0000093506238681	-0.0000000000000001	0.0031415926535899	-0.0000000000000000	
+2.1270000000000002	0.0000024352877922	0.0000047509058573	0.0000093673128873	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.1280000000000001	0.0000024108333922	0.0000047529058727	0.0000093839251630	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1290000000000000	0.0000023863269238	0.0000047549058684	0.0000094004605310	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1299999999999999	0.0000023617686291	0.0000047569058730	0.0000094169188282	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1310000000000002	0.0000023371587505	0.0000047589058619	0.0000094332998921	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1320000000000001	0.0000023124975307	0.0000047609058672	0.0000094496035611	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1330000000000000	0.0000022877852132	0.0000047629058749	0.0000094658296743	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.1339999999999999	0.0000022630220419	0.0000047649058710	0.0000094819780715	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1350000000000002	0.0000022382082613	0.0000047669058557	0.0000094980485933	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1360000000000001	0.0000022133441160	0.0000047689058717	0.0000095140410812	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.1370000000000000	0.0000021884298518	0.0000047709058697	0.0000095299553773	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1379999999999999	0.0000021634657143	0.0000047729058710	0.0000095457913245	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1390000000000002	0.0000021384519500	0.0000047749058652	0.0000095615487665	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1400000000000001	0.0000021133888057	0.0000047769058667	0.0000095772275478	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1410000000000000	0.0000020882765288	0.0000047789058687	0.0000095928275137	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1419999999999999	0.0000020631153673	0.0000047809058676	0.0000096083485103	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1430000000000002	0.0000020379055693	0.0000047829058602	0.0000096237903842	-0.0000000000000001	0.0031415926535898	-0.0000000000000000	
+2.1440000000000001	0.0000020126473837	0.0000047849058714	0.0000096391529831	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1450000000000000	0.0000019873410598	0.0000047869058732	0.0000096544361554	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1459999999999999	0.0000019619868474	0.0000047889058692	0.0000096696397503	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1470000000000002	0.0000019365849967	0.0000047909058595	0.0000096847636176	-0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.1480000000000001	0.0000019111357584	0.0000047929058694	0.0000096998076083	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1490000000000000	0.0000018856393836	0.0000047949058704	0.0000097147715736	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1499999999999999	0.0000018600961241	0.0000047969058699	0.0000097296553660	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1510000000000002	0.0000018345062319	0.0000047989058574	0.0000097444588386	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1520000000000001	0.0000018088699595	0.0000048009058722	0.0000097591818453	-0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.1530000000000000	0.0000017831875601	0.0000048029058682	0.0000097738242407	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1539999999999999	0.0000017574592870	0.0000048049058671	0.0000097883858803	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.1550000000000002	0.0000017316853943	0.0000048069058653	0.0000098028666205	0.0000000000000000	0.0031415926535897	-0.0000000000000000	
+2.1560000000000001	0.0000017058661361	0.0000048089058737	0.0000098172663182	-0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1570000000000000	0.0000016800017676	0.0000048109058677	0.0000098315848315	-0.0000000000000002	0.0031415926535898	0.0000000000000000	
+2.1579999999999999	0.0000016540925437	0.0000048129058757	0.0000098458220189	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1590000000000003	0.0000016281387204	0.0000048149058590	0.0000098599777399	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1600000000000001	0.0000016021405537	0.0000048169058710	0.0000098740518549	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1610000000000000	0.0000015760983002	0.0000048189058692	0.0000098880442249	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1619999999999999	0.0000015500122170	0.0000048209058715	0.0000099019547119	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.1630000000000003	0.0000015238825616	0.0000048229058604	0.0000099157831785	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1640000000000001	0.0000014977095917	0.0000048249058716	0.0000099295294883	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1650000000000000	0.0000014714935657	0.0000048269058696	0.0000099431935055	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1659999999999999	0.0000014452347424	0.0000048289058725	0.0000099567750954	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.1670000000000003	0.0000014189333810	0.0000048309058591	0.0000099702741238	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.1680000000000001	0.0000013925897409	0.0000048329058721	0.0000099836904577	0.0000000000000000	0.0031415926535898	-0.0000000000000000	
+2.1690000000000000	0.0000013662040823	0.0000048349058692	0.0000099970239644	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1699999999999999	0.0000013397766655	0.0000048369058682	0.0000100102745125	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1710000000000003	0.0000013133077513	0.0000048389058657	0.0000100234419712	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1720000000000002	0.0000012867976011	0.0000048409058691	0.0000100365262105	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.1730000000000000	0.0000012602464764	0.0000048429058678	0.0000100495271013	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.1739999999999999	0.0000012336546392	0.0000048449058761	0.0000100624445153	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1750000000000003	0.0000012070223522	0.0000048469058589	0.0000100752783248	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1760000000000002	0.0000011803498780	0.0000048489058693	0.0000100880284035	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1770000000000000	0.0000011536374799	0.0000048509058651	0.0000101006946252	-0.0000000000000000	0.0031415926535900	0.0000000000000001	
+2.1779999999999999	0.0000011268854216	0.0000048529058712	0.0000101132768652	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.1789999999999998	0.0000011000939671	0.0000048549058736	0.0000101257749991	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.1800000000000002	0.0000010732633809	0.0000048569058618	0.0000101381889036	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1810000000000000	0.0000010463939277	0.0000048589058678	0.0000101505184563	-0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1819999999999999	0.0000010194858727	0.0000048609058741	0.0000101627635354	-0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.1829999999999998	0.0000009925394815	0.0000048629058667	0.0000101749240200	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.1840000000000002	0.0000009655550201	0.0000048649058634	0.0000101869997902	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1850000000000001	0.0000009385327547	0.0000048669058680	0.0000101989907267	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.1859999999999999	0.0000009114729521	0.0000048689058699	0.0000102108967113	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1869999999999998	0.0000008843758794	0.0000048709058694	0.0000102227176264	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.1880000000000002	0.0000008572418040	0.0000048729058593	0.0000102344533552	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.1890000000000001	0.0000008300709935	0.0000048749058719	0.0000102461037822	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.1899999999999999	0.0000008028637164	0.0000048769058718	0.0000102576687922	-0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.1909999999999998	0.0000007756202410	0.0000048789058733	0.0000102691482710	0.0000000000000002	0.0031415926535898	0.0000000000000000	
+2.1920000000000002	0.0000007483408364	0.0000048809058589	0.0000102805421054	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.1930000000000001	0.0000007210257715	0.0000048829058677	0.0000102918501830	-0.0000000000000001	0.0031415926535898	-0.0000000000000002	
+2.1940000000000000	0.0000006936753162	0.0000048849058714	0.0000103030723921	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.1949999999999998	0.0000006662897403	0.0000048869058702	0.0000103142086220	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.1960000000000002	0.0000006388693141	0.0000048889058643	0.0000103252587627	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1970000000000001	0.0000006114143082	0.0000048909058716	0.0000103362227052	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.1980000000000000	0.0000005839249936	0.0000048929058672	0.0000103471003414	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.1989999999999998	0.0000005564016416	0.0000048949058692	0.0000103578915637	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2000000000000002	0.0000005288445239	0.0000048969058635	0.0000103685962658	-0.0000000000000001	0.0031415926535900	0.0000000000000000	
+2.2010000000000001	0.0000005012539124	0.0000048989058679	0.0000103792143420	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2020000000000000	0.0000004736300794	0.0000049009058719	0.0000103897456874	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2029999999999998	0.0000004459732976	0.0000049029058650	0.0000104001901982	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.2040000000000002	0.0000004182838400	0.0000049049058580	0.0000104105477713	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2050000000000001	0.0000003905619797	0.0000049069058724	0.0000104208183044	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2060000000000000	0.0000003628079906	0.0000049089058656	0.0000104310016961	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.2069999999999999	0.0000003350221463	0.0000049109058698	0.0000104410978461	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.2080000000000002	0.0000003072047212	0.0000049129058637	0.0000104511066545	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.2090000000000001	0.0000002793559899	0.0000049149058653	0.0000104610280226	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.2100000000000000	0.0000002514762271	0.0000049169058711	0.0000104708618526	-0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2109999999999999	0.0000002235657081	0.0000049189058742	0.0000104806080474	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2120000000000002	0.0000001956247083	0.0000049209058605	0.0000104902665107	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2130000000000001	0.0000001676535034	0.0000049229058727	0.0000104998371472	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.2140000000000000	0.0000001396523696	0.0000049249058647	0.0000105093198626	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.2149999999999999	0.0000001116215832	0.0000049269058723	0.0000105187145631	-0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.2160000000000002	0.0000000835614209	0.0000049289058565	0.0000105280211561	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2170000000000001	0.0000000554721595	0.0000049309058742	0.0000105372395497	-0.0000000000000002	0.0031415926535898	-0.0000000000000001	
+2.2180000000000000	0.0000000273540764	0.0000049329058723	0.0000105463696530	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2189999999999999	-0.0000000007925510	0.0000049349058686	0.0000105554113757	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2200000000000002	-0.0000000289674449	0.0000049369058632	0.0000105643646288	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2210000000000001	-0.0000000571703271	0.0000049389058670	0.0000105732293238	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2220000000000000	-0.0000000854009194	0.0000049409058695	0.0000105820053732	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2229999999999999	-0.0000001136589431	0.0000049429058742	0.0000105906926905	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2240000000000002	-0.0000001419441193	0.0000049449058599	0.0000105992911898	-0.0000000000000001	0.0031415926535898	-0.0000000000000002	
+2.2250000000000001	-0.0000001702561689	0.0000049469058695	0.0000106078007863	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2260000000000000	-0.0000001985948124	0.0000049489058710	0.0000106162213961	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.2269999999999999	-0.0000002269597702	0.0000049509058718	0.0000106245529360	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2280000000000002	-0.0000002553507622	0.0000049529058611	0.0000106327953237	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.2290000000000001	-0.0000002837675083	0.0000049549058712	0.0000106409484780	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.2300000000000000	-0.0000003122097280	0.0000049569058665	0.0000106490123184	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.2309999999999999	-0.0000003406771407	0.0000049589058757	0.0000106569867653	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2320000000000002	-0.0000003691694652	0.0000049609058562	0.0000106648717399	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.2330000000000001	-0.0000003976864205	0.0000049629058721	0.0000106726671645	-0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2340000000000000	-0.0000004262277251	0.0000049649058666	0.0000106803729621	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2349999999999999	-0.0000004547930973	0.0000049669058753	0.0000106879890567	-0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.2360000000000002	-0.0000004833822551	0.0000049689058558	0.0000106955153731	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.2370000000000001	-0.0000005119949164	0.0000049709058721	0.0000107029518370	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.2380000000000000	-0.0000005406307989	0.0000049729058674	0.0000107102983750	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.2389999999999999	-0.0000005692896198	0.0000049749058738	0.0000107175549147	-0.0000000000000002	0.0031415926535897	-0.0000000000000001	
+2.2400000000000002	-0.0000005979710963	0.0000049769058630	0.0000107247213843	0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2410000000000001	-0.0000006266749455	0.0000049789058671	0.0000107317977133	0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2420000000000000	-0.0000006554008838	0.0000049809058755	0.0000107387838316	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.2429999999999999	-0.0000006841486279	0.0000049829058669	0.0000107456796704	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2440000000000002	-0.0000007129178940	0.0000049849058594	0.0000107524851616	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2450000000000001	-0.0000007417083983	0.0000049869058742	0.0000107592002381	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2460000000000000	-0.0000007705198564	0.0000049889058688	0.0000107658248336	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.2469999999999999	-0.0000007993519841	0.0000049909058682	0.0000107723588826	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2480000000000002	-0.0000008282044968	0.0000049929058619	0.0000107788023208	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2490000000000001	-0.0000008570771097	0.0000049949058676	0.0000107851550845	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.2500000000000000	-0.0000008859695380	0.0000049969058748	0.0000107914171110	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2509999999999999	-0.0000009148814963	0.0000049989058730	0.0000107975883384	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2520000000000002	-0.0000009438126994	0.0000050009058587	0.0000108036687060	-0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2530000000000001	-0.0000009727628618	0.0000050029058674	0.0000108096581537	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2540000000000000	-0.0000010017316977	0.0000050049058745	0.0000108155566223	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.2549999999999999	-0.0000010307189211	0.0000050069058693	0.0000108213640537	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.2560000000000002	-0.0000010597242461	0.0000050089058661	0.0000108270803906	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.2570000000000001	-0.0000010887473863	0.0000050109058651	0.0000108327055765	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.2580000000000000	-0.0000011177880553	0.0000050129058699	0.0000108382395558	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.2589999999999999	-0.0000011468459665	0.0000050149058698	0.0000108436822741	-0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.2600000000000002	-0.0000011759208331	0.0000050169058579	0.0000108490336775	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2610000000000001	-0.0000012050123681	0.0000050189058768	0.0000108542937134	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2620000000000000	-0.0000012341202844	0.0000050209058699	0.0000108594623296	-0.0000000000000002	0.0031415926535898	-0.0000000000000001	
+2.2629999999999999	-0.0000012632442947	0.0000050229058727	0.0000108645394753	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.2640000000000002	-0.0000012923841115	0.0000050249058568	0.0000108695251002	-0.0000000000000002	0.0031415926535898	-0.0000000000000001	
+2.2650000000000001	-0.0000013215394474	0.0000050269058721	0.0000108744191554	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2660000000000000	-0.0000013507100145	0.0000050289058654	0.0000108792215922	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2669999999999999	-0.0000013798955249	0.0000050309058688	0.0000108839323636	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.2680000000000002	-0.0000014090956906	0.0000050329058609	0.0000108885514228	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.2690000000000001	-0.0000014383102234	0.0000050349058738	0.0000108930787244	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.2700000000000000	-0.0000014675388349	0.0000050369058721	0.0000108975142236	-0.0000000000000002	0.0031415926535899	-0.0000000000000001	
+2.2709999999999999	-0.0000014967812366	0.0000050389058700	0.0000109018578767	-0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.2720000000000002	-0.0000015260371401	0.0000050409058606	0.0000109061096408	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2730000000000001	-0.0000015553062565	0.0000050429058722	0.0000109102694739	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2740000000000000	-0.0000015845882969	0.0000050449058695	0.0000109143373350	0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2749999999999999	-0.0000016138829723	0.0000050469058774	0.0000109183131840	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.2760000000000002	-0.0000016431899936	0.0000050489058568	0.0000109221969815	0.0000000000000001	0.0031415926535900	0.0000000000000001	
+2.2770000000000001	-0.0000016725090717	0.0000050509058719	0.0000109259886893	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.2780000000000000	-0.0000017018399170	0.0000050529058728	0.0000109296882700	0.0000000000000002	0.0031415926535898	0.0000000000000001	
+2.2789999999999999	-0.0000017311822401	0.0000050549058668	0.0000109332956869	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.2800000000000002	-0.0000017605357515	0.0000050569058611	0.0000109368109046	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2810000000000001	-0.0000017899001614	0.0000050589058734	0.0000109402338884	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.2820000000000000	-0.0000018192751799	0.0000050609058718	0.0000109435646043	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.2829999999999999	-0.0000018486605173	0.0000050629058743	0.0000109468030197	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.2840000000000003	-0.0000018780558833	0.0000050649058594	0.0000109499491024	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.2850000000000001	-0.0000019074609881	0.0000050669058700	0.0000109530028215	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.2860000000000000	-0.0000019368755412	0.0000050689058705	0.0000109559641469	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.2869999999999999	-0.0000019662992525	0.0000050709058681	0.0000109588330492	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.2880000000000003	-0.0000019957318314	0.0000050729058628	0.0000109616095002	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.2890000000000001	-0.0000020251729876	0.0000050749058725	0.0000109642934725	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.2900000000000000	-0.0000020546224304	0.0000050769058688	0.0000109668849396	0.0000000000000000	0.0031415926535896	-0.0000000000000001	
+2.2909999999999999	-0.0000020840798693	0.0000050789058731	0.0000109693838758	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.2920000000000003	-0.0000021135450133	0.0000050809058605	0.0000109717902566	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.2930000000000001	-0.0000021430175719	0.0000050829058702	0.0000109741040583	-0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.2940000000000000	-0.0000021724972540	0.0000050849058702	0.0000109763252579	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2949999999999999	-0.0000022019837687	0.0000050869058713	0.0000109784538335	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.2960000000000003	-0.0000022314768250	0.0000050889058592	0.0000109804897641	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.2970000000000002	-0.0000022609761318	0.0000050909058732	0.0000109824330298	0.0000000000000002	0.0031415926535897	0.0000000000000000	
+2.2980000000000000	-0.0000022904813980	0.0000050929058706	0.0000109842836111	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.2989999999999999	-0.0000023199923324	0.0000050949058692	0.0000109860414900	0.0000000000000000	0.0031415926535896	-0.0000000000000001	
+2.3000000000000003	-0.0000023495086436	0.0000050969058620	0.0000109877066489	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3010000000000002	-0.0000023790300404	0.0000050989058668	0.0000109892790716	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.3020000000000000	-0.0000024085562315	0.0000051009058729	0.0000109907587425	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.3029999999999999	-0.0000024380869254	0.0000051029058733	0.0000109921456470	-0.0000000000000000	0.0031415926535896	0.0000000000000001	
+2.3040000000000003	-0.0000024676218306	0.0000051049058609	0.0000109934397713	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.3050000000000002	-0.0000024971606557	0.0000051069058713	0.0000109946411029	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3060000000000000	-0.0000025267031091	0.0000051089058690	0.0000109957496296	-0.0000000000000003	0.0031415926535897	-0.0000000000000001	
+2.3069999999999999	-0.0000025562488992	0.0000051109058753	0.0000109967653407	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3079999999999998	-0.0000025857977345	0.0000051129058655	0.0000109976882261	-0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3090000000000002	-0.0000026153493233	0.0000051149058608	0.0000109985182767	0.0000000000000000	0.0031415926535896	0.0000000000000000	
+2.3100000000000001	-0.0000026449033739	0.0000051169058719	0.0000109992554843	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.3109999999999999	-0.0000026744595947	0.0000051189058705	0.0000109998998416	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.3119999999999998	-0.0000027040176940	0.0000051209058709	0.0000110004513423	-0.0000000000000000	0.0031415926535900	0.0000000000000001	
+2.3130000000000002	-0.0000027335773799	0.0000051229058587	0.0000110009099809	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.3140000000000001	-0.0000027631383609	0.0000051249058696	0.0000110012757529	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.3149999999999999	-0.0000027927003451	0.0000051269058716	0.0000110015486547	-0.0000000000000002	0.0031415926535897	0.0000000000000000	
+2.3159999999999998	-0.0000028222630408	0.0000051289058683	0.0000110017286835	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.3170000000000002	-0.0000028518261561	0.0000051309058598	0.0000110018158377	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3180000000000001	-0.0000028813893993	0.0000051329058673	0.0000110018101164	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.3190000000000000	-0.0000029109524787	0.0000051349058732	0.0000110017115196	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.3199999999999998	-0.0000029405151025	0.0000051369058667	0.0000110015200482	-0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.3210000000000002	-0.0000029700769788	0.0000051389058622	0.0000110012357043	-0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.3220000000000001	-0.0000029996378160	0.0000051409058667	0.0000110008584905	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.3230000000000000	-0.0000030291973223	0.0000051429058768	0.0000110003884106	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.3239999999999998	-0.0000030587552058	0.0000051449058710	0.0000109998254693	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.3250000000000002	-0.0000030883111750	0.0000051469058566	0.0000109991696720	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.3260000000000001	-0.0000031178649381	0.0000051489058691	0.0000109984210254	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.3270000000000000	-0.0000031474162034	0.0000051509058730	0.0000109975795367	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3279999999999998	-0.0000031769646792	0.0000051529058682	0.0000109966452143	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.3290000000000002	-0.0000032065100740	0.0000051549058584	0.0000109956180673	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.3300000000000001	-0.0000032360520962	0.0000051569058720	0.0000109944981060	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.3310000000000000	-0.0000032655904540	0.0000051589058735	0.0000109932853414	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.3319999999999999	-0.0000032951248561	0.0000051609058699	0.0000109919797854	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.3330000000000002	-0.0000033246550110	0.0000051629058578	0.0000109905814509	0.0000000000000001	0.0031415926535899	0.0000000000000002	
+2.3340000000000001	-0.0000033541806271	0.0000051649058691	0.0000109890903518	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.3350000000000000	-0.0000033837014131	0.0000051669058754	0.0000109875065028	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.3359999999999999	-0.0000034132170776	0.0000051689058661	0.0000109858299194	0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.3370000000000002	-0.0000034427273294	0.0000051709058625	0.0000109840606182	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.3380000000000001	-0.0000034722318771	0.0000051729058681	0.0000109821986168	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.3390000000000000	-0.0000035017304296	0.0000051749058722	0.0000109802439334	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.3399999999999999	-0.0000035312226956	0.0000051769058679	0.0000109781965874	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.3410000000000002	-0.0000035607083842	0.0000051789058657	0.0000109760565989	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3420000000000001	-0.0000035901872044	0.0000051809058656	0.0000109738239891	0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.3430000000000000	-0.0000036196588652	0.0000051829058712	0.0000109714987801	0.0000000000000001	0.0031415926535900	0.0000000000000001	
+2.3439999999999999	-0.0000036491230756	0.0000051849058719	0.0000109690809947	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.3450000000000002	-0.0000036785795450	0.0000051869058640	0.0000109665706569	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.3460000000000001	-0.0000037080279826	0.0000051889058653	0.0000109639677914	0.0000000000000001	0.0031415926535897	0.0000000000000002	
+2.3470000000000000	-0.0000037374680977	0.0000051909058724	0.0000109612724239	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.3479999999999999	-0.0000037668995998	0.0000051929058709	0.0000109584845810	0.0000000000000001	0.0031415926535896	0.0000000000000000	
+2.3490000000000002	-0.0000037963221984	0.0000051949058572	0.0000109556042902	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3500000000000001	-0.0000038257356032	0.0000051969058706	0.0000109526315799	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.3510000000000000	-0.0000038551395237	0.0000051989058754	0.0000109495664796	0.0000000000000002	0.0031415926535897	0.0000000000000000	
+2.3519999999999999	-0.0000038845336699	0.0000052009058716	0.0000109464090194	-0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.3530000000000002	-0.0000039139177515	0.0000052029058592	0.0000109431592304	0.0000000000000001	0.0031415926535898	0.0000000000000002	
+2.3540000000000001	-0.0000039432914788	0.0000052049058702	0.0000109398171449	-0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.3550000000000000	-0.0000039726545615	0.0000052069058691	0.0000109363827957	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3559999999999999	-0.0000040020067101	0.0000052089058700	0.0000109328562168	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.3570000000000002	-0.0000040313476347	0.0000052109058622	0.0000109292374429	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.3580000000000001	-0.0000040606770459	0.0000052129058707	0.0000109255265098	0.0000000000000001	0.0031415926535896	0.0000000000000001	
+2.3590000000000000	-0.0000040899946541	0.0000052149058704	0.0000109217234541	-0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.3599999999999999	-0.0000041193001700	0.0000052169058686	0.0000109178283133	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3610000000000002	-0.0000041485933044	0.0000052189058617	0.0000109138411259	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.3620000000000001	-0.0000041778737681	0.0000052209058673	0.0000109097619313	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.3630000000000000	-0.0000042071412722	0.0000052229058677	0.0000109055907696	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.3639999999999999	-0.0000042363955278	0.0000052249058736	0.0000109013276821	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3650000000000002	-0.0000042656362461	0.0000052269058600	0.0000108969727109	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.3660000000000001	-0.0000042948631387	0.0000052289058696	0.0000108925258988	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.3670000000000000	-0.0000043240759169	0.0000052309058738	0.0000108879872899	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.3679999999999999	-0.0000043532742926	0.0000052329058728	0.0000108833569288	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.3690000000000002	-0.0000043824579774	0.0000052349058557	0.0000108786348614	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.3700000000000001	-0.0000044116266835	0.0000052369058724	0.0000108738211341	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3710000000000000	-0.0000044407801229	0.0000052389058659	0.0000108689157946	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.3719999999999999	-0.0000044699180079	0.0000052409058717	0.0000108639188912	0.0000000000000003	0.0031415926535896	0.0000000000000001	
+2.3730000000000002	-0.0000044990400508	0.0000052429058579	0.0000108588304732	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.3740000000000001	-0.0000045281459644	0.0000052449058741	0.0000108536505910	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.3750000000000000	-0.0000045572354613	0.0000052469058705	0.0000108483792954	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.3759999999999999	-0.0000045863082544	0.0000052489058685	0.0000108430166387	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.3770000000000002	-0.0000046153640567	0.0000052509058609	0.0000108375626738	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.3780000000000001	-0.0000046444025816	0.0000052529058690	0.0000108320174544	0.0000000000000000	0.0031415926535900	0.0000000000000001	
+2.3790000000000000	-0.0000046734235424	0.0000052549058714	0.0000108263810353	-0.0000000000000002	0.0031415926535899	-0.0000000000000001	
+2.3799999999999999	-0.0000047024266526	0.0000052569058681	0.0000108206534722	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.3810000000000002	-0.0000047314116261	0.0000052589058626	0.0000108148348214	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.3820000000000001	-0.0000047603781768	0.0000052609058691	0.0000108089251406	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.3830000000000000	-0.0000047893260187	0.0000052629058733	0.0000108029244880	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.3839999999999999	-0.0000048182548662	0.0000052649058717	0.0000107968329229	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.3850000000000002	-0.0000048471644337	0.0000052669058605	0.0000107906505052	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.3860000000000001	-0.0000048760544361	0.0000052689058683	0.0000107843772962	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.3870000000000000	-0.0000049049245880	0.0000052709058701	0.0000107780133576	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.3879999999999999	-0.0000049337746045	0.0000052729058730	0.0000107715587524	-0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3890000000000002	-0.0000049626042010	0.0000052749058591	0.0000107650135441	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.3900000000000001	-0.0000049914130929	0.0000052769058746	0.0000107583777974	0.0000000000000001	0.0031415926535896	0.0000000000000001	
+2.3910000000000000	-0.0000050202009958	0.0000052789058732	0.0000107516515779	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.3919999999999999	-0.0000050489676256	0.0000052809058692	0.0000107448349518	-0.0000000000000002	0.0031415926535898	0.0000000000000001	
+2.3930000000000002	-0.0000050777126985	0.0000052829058588	0.0000107379279864	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.3940000000000001	-0.0000051064359307	0.0000052849058670	0.0000107309307500	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.3950000000000000	-0.0000051351370387	0.0000052869058759	0.0000107238433116	0.0000000000000002	0.0031415926535897	0.0000000000000001	
+2.3959999999999999	-0.0000051638157392	0.0000052889058677	0.0000107166657411	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.3970000000000002	-0.0000051924717493	0.0000052909058637	0.0000107093981094	0.0000000000000002	0.0031415926535899	0.0000000000000001	
+2.3980000000000001	-0.0000052211047861	0.0000052929058708	0.0000107020404881	0.0000000000000002	0.0031415926535897	-0.0000000000000001	
+2.3990000000000000	-0.0000052497145669	0.0000052949058714	0.0000106945929500	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.3999999999999999	-0.0000052783008095	0.0000052969058723	0.0000106870555686	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.4010000000000002	-0.0000053068632317	0.0000052989058595	0.0000106794284181	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.4020000000000001	-0.0000053354015515	0.0000053009058718	0.0000106717115739	0.0000000000000001	0.0031415926535896	0.0000000000000001	
+2.4030000000000000	-0.0000053639154874	0.0000053029058737	0.0000106639051122	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.4039999999999999	-0.0000053924047579	0.0000053049058722	0.0000106560091099	0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.4050000000000002	-0.0000054208690818	0.0000053069058602	0.0000106480236451	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.4060000000000001	-0.0000054493081783	0.0000053089058732	0.0000106399487966	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.4070000000000000	-0.0000054777217665	0.0000053109058683	0.0000106317846440	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.4079999999999999	-0.0000055061095661	0.0000053129058777	0.0000106235312679	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4090000000000003	-0.0000055344712969	0.0000053149058620	0.0000106151887497	-0.0000000000000001	0.0031415926535898	-0.0000000000000002	
+2.4100000000000001	-0.0000055628066791	0.0000053169058710	0.0000106067571719	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.4110000000000000	-0.0000055911154328	0.0000053189058690	0.0000105982366176	-0.0000000000000002	0.0031415926535899	0.0000000000000001	
+2.4119999999999999	-0.0000056193972788	0.0000053209058774	0.0000105896271710	-0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.4130000000000003	-0.0000056476519378	0.0000053229058570	0.0000105809289169	-0.0000000000000003	0.0031415926535899	-0.0000000000000001	
+2.4140000000000001	-0.0000056758791312	0.0000053249058716	0.0000105721419412	0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.4150000000000000	-0.0000057040785802	0.0000053269058714	0.0000105632663308	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.4159999999999999	-0.0000057322500065	0.0000053289058706	0.0000105543021731	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.4170000000000003	-0.0000057603931321	0.0000053309058585	0.0000105452495566	-0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.4180000000000001	-0.0000057885076793	0.0000053329058704	0.0000105361085707	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4190000000000000	-0.0000058165933705	0.0000053349058708	0.0000105268793056	0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.4199999999999999	-0.0000058446499285	0.0000053369058703	0.0000105175618524	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.4210000000000003	-0.0000058726770765	0.0000053389058617	0.0000105081563030	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.4220000000000002	-0.0000059006745379	0.0000053409058733	0.0000104986627504	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4230000000000000	-0.0000059286420362	0.0000053429058696	0.0000104890812880	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.4239999999999999	-0.0000059565792956	0.0000053449058681	0.0000104794120107	-0.0000000000000001	0.0031415926535900	-0.0000000000000001	
+2.4250000000000003	-0.0000059844860402	0.0000053469058618	0.0000104696550137	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.4260000000000002	-0.0000060123619946	0.0000053489058718	0.0000104598103934	0.0000000000000001	0.0031415926535895	0.0000000000000000	
+2.4270000000000000	-0.0000060402068837	0.0000053509058696	0.0000104498782469	-0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4279999999999999	-0.0000060680204328	0.0000053529058730	0.0000104398586722	0.0000000000000002	0.0031415926535896	0.0000000000000000	
+2.4290000000000003	-0.0000060958023671	0.0000053549058569	0.0000104297517683	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.4300000000000002	-0.0000061235524127	0.0000053569058746	0.0000104195576350	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.4310000000000000	-0.0000061512702955	0.0000053589058656	0.0000104092763727	-0.0000000000000001	0.0031415926535896	0.0000000000000000	
+2.4319999999999999	-0.0000061789557421	0.0000053609058724	0.0000103989080830	0.0000000000000001	0.0031415926535900	-0.0000000000000001	
+2.4329999999999998	-0.0000062066084792	0.0000053629058701	0.0000103884528682	0.0000000000000000	0.0031415926535898	0.0000000000000000	
+2.4340000000000002	-0.0000062342282339	0.0000053649058657	0.0000103779108315	0.0000000000000001	0.0031415926535898	0.0000000000000002	
+2.4350000000000001	-0.0000062618147335	0.0000053669058661	0.0000103672820770	-0.0000000000000002	0.0031415926535898	0.0000000000000000	
+2.4359999999999999	-0.0000062893677058	0.0000053689058714	0.0000103565667095	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.4369999999999998	-0.0000063168868789	0.0000053709058708	0.0000103457648348	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.4380000000000002	-0.0000063443719811	0.0000053729058605	0.0000103348765595	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.4390000000000001	-0.0000063718227413	0.0000053749058725	0.0000103239019911	0.0000000000000001	0.0031415926535897	0.0000000000000001	
+2.4399999999999999	-0.0000063992388884	0.0000053769058712	0.0000103128412379	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.4409999999999998	-0.0000064266201519	0.0000053789058707	0.0000103016944091	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.4420000000000002	-0.0000064539662616	0.0000053809058601	0.0000102904616146	-0.0000000000000002	0.0031415926535899	-0.0000000000000001	
+2.4430000000000001	-0.0000064812769475	0.0000053829058750	0.0000102791429654	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.4440000000000000	-0.0000065085519401	0.0000053849058727	0.0000102677385731	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4449999999999998	-0.0000065357909702	0.0000053869058707	0.0000102562485503	-0.0000000000000002	0.0031415926535899	-0.0000000000000001	
+2.4460000000000002	-0.0000065629937689	0.0000053889058548	0.0000102446730105	0.0000000000000002	0.0031415926535898	0.0000000000000001	
+2.4470000000000001	-0.0000065901600679	0.0000053909058745	0.0000102330120677	0.0000000000000000	0.0031415926535897	0.0000000000000000	
+2.4480000000000000	-0.0000066172895989	0.0000053929058695	0.0000102212658373	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.4489999999999998	-0.0000066443820943	0.0000053949058680	0.0000102094344349	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.4500000000000002	-0.0000066714372865	0.0000053969058592	0.0000101975179776	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4510000000000001	-0.0000066984549087	0.0000053989058715	0.0000101855165827	-0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.4520000000000000	-0.0000067254346941	0.0000054009058727	0.0000101734303689	0.0000000000000002	0.0031415926535898	0.0000000000000000	
+2.4529999999999998	-0.0000067523763764	0.0000054029058700	0.0000101612594554	0.0000000000000000	0.0031415926535898	0.0000000000000001	
+2.4540000000000002	-0.0000067792796898	0.0000054049058631	0.0000101490039623	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.4550000000000001	-0.0000068061443688	0.0000054069058697	0.0000101366640105	0.0000000000000000	0.0031415926535897	-0.0000000000000001	
+2.4560000000000000	-0.0000068329701481	0.0000054089058720	0.0000101242397219	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.4569999999999999	-0.0000068597567631	0.0000054109058698	0.0000101117312191	-0.0000000000000003	0.0031415926535898	-0.0000000000000001	
+2.4580000000000002	-0.0000068865039493	0.0000054129058594	0.0000100991386255	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.4590000000000001	-0.0000069132114428	0.0000054149058728	0.0000100864620654	0.0000000000000000	0.0031415926535896	-0.0000000000000001	
+2.4600000000000000	-0.0000069398789800	0.0000054169058707	0.0000100737016639	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4609999999999999	-0.0000069665062976	0.0000054189058708	0.0000100608575471	-0.0000000000000002	0.0031415926535899	0.0000000000000000	
+2.4620000000000002	-0.0000069930931330	0.0000054209058588	0.0000100479298415	-0.0000000000000002	0.0031415926535899	-0.0000000000000002	
+2.4630000000000001	-0.0000070196392236	0.0000054229058700	0.0000100349186749	0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.4640000000000000	-0.0000070461443075	0.0000054249058688	0.0000100218241756	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.4649999999999999	-0.0000070726081231	0.0000054269058728	0.0000100086464729	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.4660000000000002	-0.0000070990304092	0.0000054289058607	0.0000099953856969	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.4670000000000001	-0.0000071254109050	0.0000054309058714	0.0000099820419783	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.4680000000000000	-0.0000071517493502	0.0000054329058691	0.0000099686154490	-0.0000000000000001	0.0031415926535899	-0.0000000000000001	
+2.4689999999999999	-0.0000071780454848	0.0000054349058717	0.0000099551062414	0.0000000000000001	0.0031415926535899	0.0000000000000001	
+2.4700000000000002	-0.0000072042990492	0.0000054369058575	0.0000099415144888	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.4710000000000001	-0.0000072305097845	0.0000054389058728	0.0000099278403255	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.4720000000000000	-0.0000072566774318	0.0000054409058711	0.0000099140838863	-0.0000000000000001	0.0031415926535900	0.0000000000000000	
+2.4729999999999999	-0.0000072828017329	0.0000054429058701	0.0000099002453071	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4740000000000002	-0.0000073088824300	0.0000054449058590	0.0000098863247243	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.4750000000000001	-0.0000073349192657	0.0000054469058733	0.0000098723222755	0.0000000000000000	0.0031415926535897	0.0000000000000001	
+2.4760000000000000	-0.0000073609119829	0.0000054489058736	0.0000098582380988	0.0000000000000000	0.0031415926535899	0.0000000000000001	
+2.4769999999999999	-0.0000073868603252	0.0000054509058706	0.0000098440723332	0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4780000000000002	-0.0000074127640365	0.0000054529058605	0.0000098298251184	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.4790000000000001	-0.0000074386228610	0.0000054549058682	0.0000098154965953	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.4800000000000000	-0.0000074644365437	0.0000054569058720	0.0000098010869050	0.0000000000000000	0.0031415926535898	-0.0000000000000001	
+2.4809999999999999	-0.0000074902048297	0.0000054589058720	0.0000097865961900	-0.0000000000000001	0.0031415926535897	-0.0000000000000001	
+2.4820000000000002	-0.0000075159274646	0.0000054609058572	0.0000097720245931	-0.0000000000000001	0.0031415926535897	0.0000000000000000	
+2.4830000000000001	-0.0000075416041947	0.0000054629058703	0.0000097573722582	0.0000000000000000	0.0031415926535899	-0.0000000000000001	
+2.4840000000000000	-0.0000075672347664	0.0000054649058684	0.0000097426393300	-0.0000000000000001	0.0031415926535897	0.0000000000000002	
+2.4849999999999999	-0.0000075928189270	0.0000054669058727	0.0000097278259537	-0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4860000000000002	-0.0000076183564237	0.0000054689058617	0.0000097129322757	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4870000000000001	-0.0000076438470046	0.0000054709058745	0.0000096979584429	-0.0000000000000001	0.0031415926535898	-0.0000000000000001	
+2.4880000000000000	-0.0000076692904181	0.0000054729058681	0.0000096829046031	0.0000000000000001	0.0031415926535899	0.0000000000000002	
+2.4889999999999999	-0.0000076946864131	0.0000054749058710	0.0000096677709049	-0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4900000000000002	-0.0000077200347390	0.0000054769058616	0.0000096525574976	0.0000000000000001	0.0031415926535899	0.0000000000000000	
+2.4910000000000001	-0.0000077453351455	0.0000054789058717	0.0000096372645314	-0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.4920000000000000	-0.0000077705873830	0.0000054809058694	0.0000096218921573	-0.0000000000000001	0.0031415926535900	-0.0000000000000002	
+2.4929999999999999	-0.0000077957912022	0.0000054829058720	0.0000096064405269	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4940000000000002	-0.0000078209463543	0.0000054849058583	0.0000095909097927	0.0000000000000001	0.0031415926535898	0.0000000000000000	
+2.4950000000000001	-0.0000078460525912	0.0000054869058742	0.0000095753001081	0.0000000000000000	0.0031415926535899	0.0000000000000000	
+2.4960000000000000	-0.0000078711096650	0.0000054889058699	0.0000095596116270	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.4969999999999999	-0.0000078961173284	0.0000054909058701	0.0000095438445044	-0.0000000000000001	0.0031415926535900	-0.0000000000000001	
+2.4980000000000002	-0.0000079210753346	0.0000054929058639	0.0000095279988958	0.0000000000000001	0.0031415926535897	0.0000000000000002	
+2.4990000000000001	-0.0000079459834372	0.0000054949058690	0.0000095120749577	-0.0000000000000002	0.0031415926535898	-0.0000000000000001	
+2.5000000000000000	-0.0000079708413906	0.0000054969058710	0.0000094960728472	0.0000000000000001	0.0031415926535898	0.0000000000000001	
+2.5009999999999999	-0.0000079956489492	0.0000054989058734	0.0000094799927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5020000000000002	-0.0000079906489491	0.0000055009058563	0.0000094889927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5030000000000001	-0.0000079856489492	0.0000055029058676	0.0000094979927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5040000000000000	-0.0000079806489492	0.0000055049058719	0.0000095069927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5049999999999999	-0.0000079756489492	0.0000055069058690	0.0000095159927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5060000000000002	-0.0000079706489491	0.0000055089058590	0.0000095249927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5070000000000001	-0.0000079656489492	0.0000055109058704	0.0000095339927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5080000000000000	-0.0000079606489492	0.0000055129058675	0.0000095429927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5089999999999999	-0.0000079556489492	0.0000055149058717	0.0000095519927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5100000000000002	-0.0000079506489491	0.0000055169058582	0.0000095609927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5110000000000001	-0.0000079456489492	0.0000055189058695	0.0000095699927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5120000000000000	-0.0000079406489492	0.0000055209058667	0.0000095789927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5129999999999999	-0.0000079356489492	0.0000055229058744	0.0000095879927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5140000000000002	-0.0000079306489491	0.0000055249058574	0.0000095969927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5150000000000001	-0.0000079256489492	0.0000055269058687	0.0000096059927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5160000000000000	-0.0000079206489492	0.0000055289058694	0.0000096149927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5169999999999999	-0.0000079156489492	0.0000055309058701	0.0000096239927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5180000000000002	-0.0000079106489491	0.0000055329058565	0.0000096329927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5190000000000001	-0.0000079056489492	0.0000055349058714	0.0000096419927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5200000000000000	-0.0000079006489491	0.0000055369058650	0.0000096509927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5209999999999999	-0.0000078956489492	0.0000055389058728	0.0000096599927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5220000000000002	-0.0000078906489491	0.0000055409058593	0.0000096689927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5230000000000001	-0.0000078856489492	0.0000055429058706	0.0000096779927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5240000000000000	-0.0000078806489492	0.0000055449058713	0.0000096869927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5249999999999999	-0.0000078756489492	0.0000055469058684	0.0000096959927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5260000000000002	-0.0000078706489491	0.0000055489058584	0.0000097049927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5270000000000001	-0.0000078656489492	0.0000055509058698	0.0000097139927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5280000000000000	-0.0000078606489492	0.0000055529058705	0.0000097229927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5289999999999999	-0.0000078556489491	0.0000055549058640	0.0000097319927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5300000000000002	-0.0000078506489491	0.0000055569058647	0.0000097409927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5310000000000001	-0.0000078456489492	0.0000055589058689	0.0000097499927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5320000000000000	-0.0000078406489492	0.0000055609058661	0.0000097589927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5329999999999999	-0.0000078356489492	0.0000055629058739	0.0000097679927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5340000000000003	-0.0000078306489491	0.0000055649058568	0.0000097769927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5350000000000001	-0.0000078256489492	0.0000055669058717	0.0000097859927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5360000000000000	-0.0000078206489492	0.0000055689058688	0.0000097949927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5369999999999999	-0.0000078156489492	0.0000055709058695	0.0000098039927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5380000000000003	-0.0000078106489491	0.0000055729058595	0.0000098129927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5390000000000001	-0.0000078056489492	0.0000055749058708	0.0000098219927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5400000000000000	-0.0000078006489492	0.0000055769058715	0.0000098309927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5409999999999999	-0.0000077956489492	0.0000055789058687	0.0000098399927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5420000000000003	-0.0000077906489491	0.0000055809058587	0.0000098489927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5430000000000001	-0.0000077856489492	0.0000055829058700	0.0000098579927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5440000000000000	-0.0000077806489492	0.0000055849058707	0.0000098669927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5449999999999999	-0.0000077756489492	0.0000055869058714	0.0000098759927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5460000000000003	-0.0000077706489491	0.0000055889058543	0.0000098849927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5470000000000002	-0.0000077656489492	0.0000055909058727	0.0000098939927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5480000000000000	-0.0000077606489492	0.0000055929058699	0.0000099029927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5489999999999999	-0.0000077556489492	0.0000055949058706	0.0000099119927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5500000000000003	-0.0000077506489491	0.0000055969058570	0.0000099209927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5510000000000002	-0.0000077456489492	0.0000055989058719	0.0000099299927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5520000000000000	-0.0000077406489492	0.0000056009058690	0.0000099389927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5529999999999999	-0.0000077356489492	0.0000056029058697	0.0000099479927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5540000000000003	-0.0000077306489491	0.0000056049058597	0.0000099569927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5550000000000002	-0.0000077256489492	0.0000056069058711	0.0000099659927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5560000000000000	-0.0000077206489492	0.0000056089058682	0.0000099749927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5569999999999999	-0.0000077156489492	0.0000056109058760	0.0000099839927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5580000000000003	-0.0000077106489491	0.0000056129058589	0.0000099929927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5590000000000002	-0.0000077056489492	0.0000056149058774	0.0000100019927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5600000000000001	-0.0000077006489492	0.0000056169058674	0.0000100109927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5609999999999999	-0.0000076956489492	0.0000056189058787	0.0000100199927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5619999999999998	-0.0000076906489492	0.0000056209058688	0.0000100289927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5630000000000002	-0.0000076856489492	0.0000056229058659	0.0000100379927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5640000000000001	-0.0000076806489492	0.0000056249058772	0.0000100469927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5649999999999999	-0.0000076756489492	0.0000056269058672	0.0000100559927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5659999999999998	-0.0000076706489492	0.0000056289058786	0.0000100649927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5670000000000002	-0.0000076656489491	0.0000056309058544	0.0000100739927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5680000000000001	-0.0000076606489492	0.0000056329058728	0.0000100829927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5690000000000000	-0.0000076556489492	0.0000056349058771	0.0000100919927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5699999999999998	-0.0000076506489492	0.0000056369058742	0.0000101009927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5710000000000002	-0.0000076456489491	0.0000056389058642	0.0000101099927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5720000000000001	-0.0000076406489492	0.0000056409058685	0.0000101189927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5730000000000000	-0.0000076356489492	0.0000056429058727	0.0000101279927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5739999999999998	-0.0000076306489492	0.0000056449058769	0.0000101369927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5750000000000002	-0.0000076256489491	0.0000056469058598	0.0000101459927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5760000000000001	-0.0000076206489492	0.0000056489058783	0.0000101549927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5770000000000000	-0.0000076156489492	0.0000056509058754	0.0000101639927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5779999999999998	-0.0000076106489492	0.0000056529058725	0.0000101729927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5790000000000002	-0.0000076056489491	0.0000056549058555	0.0000101819927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5800000000000001	-0.0000076006489492	0.0000056569058739	0.0000101909927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5810000000000000	-0.0000075956489492	0.0000056589058781	0.0000101999927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5819999999999999	-0.0000075906489492	0.0000056609058682	0.0000102089927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5830000000000002	-0.0000075856489491	0.0000056629058653	0.0000102179927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5840000000000001	-0.0000075806489492	0.0000056649058766	0.0000102269927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5850000000000000	-0.0000075756489492	0.0000056669058738	0.0000102359927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5859999999999999	-0.0000075706489491	0.0000056689058638	0.0000102449927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5870000000000002	-0.0000075656489492	0.0000056709058680	0.0000102539927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5880000000000001	-0.0000075606489492	0.0000056729058723	0.0000102629927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5890000000000000	-0.0000075556489492	0.0000056749058765	0.0000102719927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5899999999999999	-0.0000075506489492	0.0000056769058736	0.0000102809927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5910000000000002	-0.0000075456489491	0.0000056789058636	0.0000102899927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5920000000000001	-0.0000075406489492	0.0000056809058750	0.0000102989927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5930000000000000	-0.0000075356489491	0.0000056829058650	0.0000103079927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5939999999999999	-0.0000075306489492	0.0000056849058763	0.0000103169927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5950000000000002	-0.0000075256489492	0.0000056869058664	0.0000103259927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5960000000000001	-0.0000075206489491	0.0000056889058635	0.0000103349927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5970000000000000	-0.0000075156489492	0.0000056909058819	0.0000103439927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5979999999999999	-0.0000075106489492	0.0000056929058720	0.0000103529927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.5990000000000002	-0.0000075056489491	0.0000056949058620	0.0000103619927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6000000000000001	-0.0000075006489492	0.0000056969058733	0.0000103709927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6010000000000000	-0.0000074956489492	0.0000056989058705	0.0000103799927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6019999999999999	-0.0000074906489492	0.0000057009058747	0.0000103889927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6030000000000002	-0.0000074856489491	0.0000057029058576	0.0000103979927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6040000000000001	-0.0000074806489492	0.0000057049058761	0.0000104069927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6050000000000000	-0.0000074756489492	0.0000057069058803	0.0000104159927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6059999999999999	-0.0000074706489492	0.0000057089058703	0.0000104249927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6070000000000002	-0.0000074656489491	0.0000057109058603	0.0000104339927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6080000000000001	-0.0000074606489492	0.0000057129058717	0.0000104429927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6090000000000000	-0.0000074556489492	0.0000057149058759	0.0000104519927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6099999999999999	-0.0000074506489492	0.0000057169058730	0.0000104609927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6110000000000002	-0.0000074456489491	0.0000057189058631	0.0000104699927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6120000000000001	-0.0000074406489492	0.0000057209058744	0.0000104789927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6130000000000000	-0.0000074356489492	0.0000057229058715	0.0000104879927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6139999999999999	-0.0000074306489492	0.0000057249058687	0.0000104969927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6150000000000002	-0.0000074256489492	0.0000057269058658	0.0000105059927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6160000000000001	-0.0000074206489492	0.0000057289058700	0.0000105149927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6170000000000000	-0.0000074156489492	0.0000057309058743	0.0000105239927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6179999999999999	-0.0000074106489492	0.0000057329058785	0.0000105329927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6190000000000002	-0.0000074056489491	0.0000057349058614	0.0000105419927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6200000000000001	-0.0000074006489492	0.0000057369058727	0.0000105509927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6210000000000000	-0.0000073956489492	0.0000057389058699	0.0000105599927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6219999999999999	-0.0000073906489492	0.0000057409058741	0.0000105689927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6230000000000002	-0.0000073856489491	0.0000057429058641	0.0000105779927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6240000000000001	-0.0000073806489492	0.0000057449058684	0.0000105869927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6250000000000000	-0.0000073756489492	0.0000057469058797	0.0000105959927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6259999999999999	-0.0000073706489492	0.0000057489058697	0.0000106049927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6270000000000002	-0.0000073656489492	0.0000057509058669	0.0000106139927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6280000000000001	-0.0000073606489491	0.0000057529058640	0.0000106229927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6290000000000000	-0.0000073556489492	0.0000057549058753	0.0000106319927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6299999999999999	-0.0000073506489492	0.0000057569058796	0.0000106409927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6310000000000002	-0.0000073456489491	0.0000057589058554	0.0000106499927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6320000000000001	-0.0000073406489492	0.0000057609058809	0.0000106589927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6330000000000000	-0.0000073356489492	0.0000057629058709	0.0000106679927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6339999999999999	-0.0000073306489492	0.0000057649058681	0.0000106769927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6350000000000002	-0.0000073256489491	0.0000057669058652	0.0000106859927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6360000000000001	-0.0000073206489492	0.0000057689058765	0.0000106949927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6370000000000000	-0.0000073156489492	0.0000057709058666	0.0000107039927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6379999999999999	-0.0000073106489492	0.0000057729058779	0.0000107129927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6390000000000002	-0.0000073056489491	0.0000057749058608	0.0000107219927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6400000000000001	-0.0000073006489492	0.0000057769058722	0.0000107309927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6410000000000000	-0.0000072956489492	0.0000057789058764	0.0000107399927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6419999999999999	-0.0000072906489492	0.0000057809058664	0.0000107489927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6430000000000002	-0.0000072856489492	0.0000057829058707	0.0000107579927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6440000000000001	-0.0000072806489492	0.0000057849058678	0.0000107669927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6450000000000000	-0.0000072756489492	0.0000057869058720	0.0000107759927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6459999999999999	-0.0000072706489492	0.0000057889058762	0.0000107849927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6470000000000002	-0.0000072656489492	0.0000057909058663	0.0000107939927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6480000000000001	-0.0000072606489492	0.0000057929058705	0.0000108029927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6490000000000000	-0.0000072556489492	0.0000057949058676	0.0000108119927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6499999999999999	-0.0000072506489492	0.0000057969058719	0.0000108209927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6510000000000002	-0.0000072456489492	0.0000057989058690	0.0000108299927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6520000000000001	-0.0000072406489492	0.0000058009058661	0.0000108389927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6530000000000000	-0.0000072356489492	0.0000058029058775	0.0000108479927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6539999999999999	-0.0000072306489492	0.0000058049058746	0.0000108569927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6550000000000002	-0.0000072256489491	0.0000058069058646	0.0000108659927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6560000000000001	-0.0000072206489492	0.0000058089058689	0.0000108749927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6570000000000000	-0.0000072156489492	0.0000058109058731	0.0000108839927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6579999999999999	-0.0000072106489492	0.0000058129058702	0.0000108929927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6590000000000003	-0.0000072056489491	0.0000058149058602	0.0000109019927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6600000000000001	-0.0000072006489492	0.0000058169058787	0.0000109109927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6610000000000000	-0.0000071956489492	0.0000058189058758	0.0000109199927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6619999999999999	-0.0000071906489492	0.0000058209058729	0.0000109289927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6630000000000003	-0.0000071856489491	0.0000058229058559	0.0000109379927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6640000000000001	-0.0000071806489492	0.0000058249058743	0.0000109469927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6650000000000000	-0.0000071756489492	0.0000058269058785	0.0000109559927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6659999999999999	-0.0000071706489492	0.0000058289058686	0.0000109649927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6670000000000003	-0.0000071656489491	0.0000058309058586	0.0000109739927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6680000000000001	-0.0000071606489492	0.0000058329058770	0.0000109829927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6690000000000000	-0.0000071556489492	0.0000058349058742	0.0000109919927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6699999999999999	-0.0000071506489492	0.0000058369058784	0.0000110009927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6710000000000003	-0.0000071456489491	0.0000058389058613	0.0000110099927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6720000000000002	-0.0000071406489492	0.0000058409058726	0.0000110189927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6730000000000000	-0.0000071356489492	0.0000058429058698	0.0000110279927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6739999999999999	-0.0000071306489492	0.0000058449058811	0.0000110369927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6750000000000003	-0.0000071256489491	0.0000058469058569	0.0000110459927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6760000000000002	-0.0000071206489492	0.0000058489058754	0.0000110549927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6770000000000000	-0.0000071156489492	0.0000058509058796	0.0000110639927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6779999999999999	-0.0000071106489492	0.0000058529058696	0.0000110729927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6790000000000003	-0.0000071056489491	0.0000058549058597	0.0000110819927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6800000000000002	-0.0000071006489492	0.0000058569058710	0.0000110909927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6810000000000000	-0.0000070956489492	0.0000058589058823	0.0000110999927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6819999999999999	-0.0000070906489492	0.0000058609058724	0.0000111089927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6830000000000003	-0.0000070856489491	0.0000058629058624	0.0000111179927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6840000000000002	-0.0000070806489492	0.0000058649058737	0.0000111269927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6850000000000001	-0.0000070756489492	0.0000058669058780	0.0000111359927222	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6859999999999999	-0.0000070706489492	0.0000058689058751	0.0000111449927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6870000000000003	-0.0000070656489491	0.0000058709058580	0.0000111539927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6880000000000002	-0.0000070606489492	0.0000058729058764	0.0000111629927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6890000000000001	-0.0000070556489492	0.0000058749058736	0.0000111719927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6899999999999999	-0.0000070506489492	0.0000058769058707	0.0000111809927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6909999999999998	-0.0000070456489492	0.0000058789058749	0.0000111899927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6920000000000002	-0.0000070406489491	0.0000058809058650	0.0000111989927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6930000000000001	-0.0000070356489492	0.0000058829058763	0.0000112079927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6940000000000000	-0.0000070306489492	0.0000058849058663	0.0000112169927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6949999999999998	-0.0000070256489492	0.0000058869058777	0.0000112259927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6960000000000002	-0.0000070206489491	0.0000058889058606	0.0000112349927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6970000000000001	-0.0000070156489492	0.0000058909058790	0.0000112439927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6980000000000000	-0.0000070106489492	0.0000058929058690	0.0000112529927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.6989999999999998	-0.0000070056489492	0.0000058949058804	0.0000112619927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7000000000000002	-0.0000070006489491	0.0000058969058633	0.0000112709927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7010000000000001	-0.0000069956489492	0.0000058989058675	0.0000112799927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7020000000000000	-0.0000069906489492	0.0000059009058789	0.0000112889927222	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7029999999999998	-0.0000069856489492	0.0000059029058689	0.0000112979927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7040000000000002	-0.0000069806489492	0.0000059049058660	0.0000113069927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7050000000000001	-0.0000069756489492	0.0000059069058774	0.0000113159927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7060000000000000	-0.0000069706489492	0.0000059089058745	0.0000113249927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7069999999999999	-0.0000069656489491	0.0000059109058645	0.0000113339927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7080000000000002	-0.0000069606489492	0.0000059129058688	0.0000113429927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7090000000000001	-0.0000069556489492	0.0000059149058730	0.0000113519927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7100000000000000	-0.0000069506489492	0.0000059169058701	0.0000113609927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7109999999999999	-0.0000069456489492	0.0000059189058744	0.0000113699927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7120000000000002	-0.0000069406489491	0.0000059209058644	0.0000113789927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7130000000000001	-0.0000069356489492	0.0000059229058757	0.0000113879927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7140000000000000	-0.0000069306489492	0.0000059249058728	0.0000113969927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7149999999999999	-0.0000069256489492	0.0000059269058700	0.0000114059927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7160000000000002	-0.0000069206489492	0.0000059289058671	0.0000114149927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7170000000000001	-0.0000069156489492	0.0000059309058713	0.0000114239927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7180000000000000	-0.0000069106489492	0.0000059329058756	0.0000114329927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7189999999999999	-0.0000069056489492	0.0000059349058727	0.0000114419927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7200000000000002	-0.0000069006489491	0.0000059369058627	0.0000114509927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7210000000000001	-0.0000068956489492	0.0000059389058741	0.0000114599927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7220000000000000	-0.0000068906489492	0.0000059409058712	0.0000114689927222	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7229999999999999	-0.0000068856489492	0.0000059429058754	0.0000114779927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7240000000000002	-0.0000068806489491	0.0000059449058654	0.0000114869927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7250000000000001	-0.0000068756489492	0.0000059469058697	0.0000114959927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7260000000000000	-0.0000068706489492	0.0000059489058739	0.0000115049927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7269999999999999	-0.0000068656489492	0.0000059509058781	0.0000115139927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7280000000000002	-0.0000068606489491	0.0000059529058611	0.0000115229927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7290000000000001	-0.0000068556489492	0.0000059549058724	0.0000115319927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7300000000000000	-0.0000068506489492	0.0000059569058766	0.0000115409927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7309999999999999	-0.0000068456489492	0.0000059589058738	0.0000115499927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7320000000000002	-0.0000068406489491	0.0000059609058567	0.0000115589927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7330000000000001	-0.0000068356489492	0.0000059629058751	0.0000115679927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7340000000000000	-0.0000068306489492	0.0000059649058794	0.0000115769927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7349999999999999	-0.0000068256489492	0.0000059669058765	0.0000115859927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7360000000000002	-0.0000068206489491	0.0000059689058594	0.0000115949927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7370000000000001	-0.0000068156489492	0.0000059709058708	0.0000116039927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7380000000000000	-0.0000068106489492	0.0000059729058750	0.0000116129927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7389999999999999	-0.0000068056489492	0.0000059749058721	0.0000116219927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7400000000000002	-0.0000068006489492	0.0000059769058692	0.0000116309927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7410000000000001	-0.0000067956489492	0.0000059789058735	0.0000116399927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7420000000000000	-0.0000067906489492	0.0000059809058706	0.0000116489927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7429999999999999	-0.0000067856489492	0.0000059829058677	0.0000116579927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7440000000000002	-0.0000067806489491	0.0000059849058649	0.0000116669927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7450000000000001	-0.0000067756489492	0.0000059869058762	0.0000116759927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7460000000000000	-0.0000067706489492	0.0000059889058733	0.0000116849927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7469999999999999	-0.0000067656489492	0.0000059909058705	0.0000116939927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7480000000000002	-0.0000067606489492	0.0000059929058676	0.0000117029927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7490000000000001	-0.0000067556489492	0.0000059949058718	0.0000117119927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7500000000000000	-0.0000067506489492	0.0000059969058690	0.0000117209927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7509999999999999	-0.0000067456489492	0.0000059989058803	0.0000117299927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7520000000000002	-0.0000067406489491	0.0000060009058561	0.0000117389927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7530000000000001	-0.0000067356489492	0.0000060029058745	0.0000117479927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7540000000000000	-0.0000067306489492	0.0000060049058788	0.0000117569927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7549999999999999	-0.0000067256489492	0.0000060069058759	0.0000117659927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7560000000000002	-0.0000067206489491	0.0000060089058588	0.0000117749927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7570000000000001	-0.0000067156489492	0.0000060109058702	0.0000117839927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7580000000000000	-0.0000067106489492	0.0000060129058815	0.0000117929927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7589999999999999	-0.0000067056489491	0.0000060149058644	0.0000118019927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7600000000000002	-0.0000067006489492	0.0000060169058687	0.0000118109927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7610000000000001	-0.0000066956489492	0.0000060189058729	0.0000118199927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7620000000000000	-0.0000066906489492	0.0000060209058771	0.0000118289927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7629999999999999	-0.0000066856489492	0.0000060229058743	0.0000118379927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7640000000000002	-0.0000066806489491	0.0000060249058572	0.0000118469927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7650000000000001	-0.0000066756489492	0.0000060269058756	0.0000118559927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7660000000000000	-0.0000066706489492	0.0000060289058727	0.0000118649927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7669999999999999	-0.0000066656489492	0.0000060309058699	0.0000118739927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7680000000000002	-0.0000066606489492	0.0000060329058670	0.0000118829927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7690000000000001	-0.0000066556489492	0.0000060349058783	0.0000118919927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7700000000000000	-0.0000066506489492	0.0000060369058684	0.0000119009927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7709999999999999	-0.0000066456489492	0.0000060389058726	0.0000119099927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7720000000000002	-0.0000066406489491	0.0000060409058626	0.0000119189927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7730000000000001	-0.0000066356489492	0.0000060429058740	0.0000119279927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7740000000000000	-0.0000066306489492	0.0000060449058711	0.0000119369927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7749999999999999	-0.0000066256489492	0.0000060469058753	0.0000119459927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7760000000000002	-0.0000066206489491	0.0000060489058654	0.0000119549927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7770000000000001	-0.0000066156489492	0.0000060509058696	0.0000119639927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7780000000000000	-0.0000066106489492	0.0000060529058738	0.0000119729927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7789999999999999	-0.0000066056489492	0.0000060549058709	0.0000119819927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7800000000000002	-0.0000066006489492	0.0000060569058681	0.0000119909927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7810000000000001	-0.0000065956489492	0.0000060589058723	0.0000119999927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7820000000000000	-0.0000065906489492	0.0000060609058765	0.0000120089927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7829999999999999	-0.0000065856489492	0.0000060629058737	0.0000120179927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7840000000000003	-0.0000065806489491	0.0000060649058637	0.0000120269927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7850000000000001	-0.0000065756489492	0.0000060669058679	0.0000120359927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7860000000000000	-0.0000065706489492	0.0000060689058722	0.0000120449927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7869999999999999	-0.0000065656489492	0.0000060709058764	0.0000120539927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7880000000000003	-0.0000065606489491	0.0000060729058593	0.0000120629927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7890000000000001	-0.0000065556489492	0.0000060749058778	0.0000120719927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7900000000000000	-0.0000065506489492	0.0000060769058749	0.0000120809927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7909999999999999	-0.0000065456489492	0.0000060789058720	0.0000120899927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7920000000000003	-0.0000065406489491	0.0000060809058620	0.0000120989927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7930000000000001	-0.0000065356489492	0.0000060829058734	0.0000121079927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7940000000000000	-0.0000065306489492	0.0000060849058705	0.0000121169927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7949999999999999	-0.0000065256489492	0.0000060869058747	0.0000121259927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7960000000000003	-0.0000065206489491	0.0000060889058648	0.0000121349927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7970000000000002	-0.0000065156489492	0.0000060909058690	0.0000121439927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7980000000000000	-0.0000065106489492	0.0000060929058803	0.0000121529927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.7989999999999999	-0.0000065056489492	0.0000060949058704	0.0000121619927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8000000000000003	-0.0000065006489491	0.0000060969058604	0.0000121709927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8010000000000002	-0.0000064956489492	0.0000060989058717	0.0000121799927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8020000000000000	-0.0000064906489492	0.0000061009058760	0.0000121889927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8029999999999999	-0.0000064856489492	0.0000061029058802	0.0000121979927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8040000000000003	-0.0000064806489491	0.0000061049058560	0.0000122069927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8050000000000002	-0.0000064756489492	0.0000061069058745	0.0000122159927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8060000000000000	-0.0000064706489492	0.0000061089058716	0.0000122249927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8069999999999999	-0.0000064656489492	0.0000061109058758	0.0000122339927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8080000000000003	-0.0000064606489491	0.0000061129058587	0.0000122429927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8090000000000002	-0.0000064556489492	0.0000061149058701	0.0000122519927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8100000000000001	-0.0000064506489492	0.0000061169058814	0.0000122609927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8109999999999999	-0.0000064456489492	0.0000061189058785	0.0000122699927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8120000000000003	-0.0000064406489491	0.0000061209058544	0.0000122789927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8130000000000002	-0.0000064356489492	0.0000061229058728	0.0000122879927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8140000000000001	-0.0000064306489492	0.0000061249058770	0.0000122969927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8149999999999999	-0.0000064256489492	0.0000061269058742	0.0000123059927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8159999999999998	-0.0000064206489492	0.0000061289058713	0.0000123149927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8170000000000002	-0.0000064156489491	0.0000061309058613	0.0000123239927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8180000000000001	-0.0000064106489492	0.0000061329058727	0.0000123329927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8190000000000000	-0.0000064056489492	0.0000061349058769	0.0000123419927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8199999999999998	-0.0000064006489492	0.0000061369058669	0.0000123509927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8210000000000002	-0.0000063956489492	0.0000061389058711	0.0000123599927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8220000000000001	-0.0000063906489492	0.0000061409058683	0.0000123689927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8230000000000000	-0.0000063856489492	0.0000061429058725	0.0000123779927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8239999999999998	-0.0000063806489492	0.0000061449058767	0.0000123869927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8250000000000002	-0.0000063756489491	0.0000061469058597	0.0000123959927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8260000000000001	-0.0000063706489492	0.0000061489058781	0.0000124049927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8270000000000000	-0.0000063656489492	0.0000061509058681	0.0000124139927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8279999999999998	-0.0000063606489492	0.0000061529058724	0.0000124229927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8290000000000002	-0.0000063556489491	0.0000061549058624	0.0000124319927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8300000000000001	-0.0000063506489492	0.0000061569058737	0.0000124409927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8310000000000000	-0.0000063456489492	0.0000061589058709	0.0000124499927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8319999999999999	-0.0000063406489492	0.0000061609058822	0.0000124589927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8330000000000002	-0.0000063356489491	0.0000061629058580	0.0000124679927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8340000000000001	-0.0000063306489492	0.0000061649058693	0.0000124769927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8350000000000000	-0.0000063256489492	0.0000061669058807	0.0000124859927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8359999999999999	-0.0000063206489492	0.0000061689058707	0.0000124949927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8370000000000002	-0.0000063156489491	0.0000061709058607	0.0000125039927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8380000000000001	-0.0000063106489492	0.0000061729058721	0.0000125129927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8390000000000000	-0.0000063056489492	0.0000061749058763	0.0000125219927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8399999999999999	-0.0000063006489492	0.0000061769058663	0.0000125309927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8410000000000002	-0.0000062956489491	0.0000061789058635	0.0000125399927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8420000000000001	-0.0000062906489492	0.0000061809058748	0.0000125489927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8430000000000000	-0.0000062856489492	0.0000061829058719	0.0000125579927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8439999999999999	-0.0000062806489492	0.0000061849058691	0.0000125669927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8450000000000002	-0.0000062756489492	0.0000061869058733	0.0000125759927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8460000000000001	-0.0000062706489492	0.0000061889058704	0.0000125849927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8470000000000000	-0.0000062656489492	0.0000061909058746	0.0000125939927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8479999999999999	-0.0000062606489492	0.0000061929058789	0.0000126029927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8490000000000002	-0.0000062556489491	0.0000061949058618	0.0000126119927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8500000000000001	-0.0000062506489492	0.0000061969058731	0.0000126209927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8510000000000000	-0.0000062456489492	0.0000061989058703	0.0000126299927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8519999999999999	-0.0000062406489492	0.0000062009058745	0.0000126389927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8530000000000002	-0.0000062356489491	0.0000062029058645	0.0000126479927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8540000000000001	-0.0000062306489492	0.0000062049058688	0.0000126569927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8550000000000000	-0.0000062256489492	0.0000062069058801	0.0000126659927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8559999999999999	-0.0000062206489492	0.0000062089058843	0.0000126749927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8570000000000002	-0.0000062156489491	0.0000062109058601	0.0000126839927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8580000000000001	-0.0000062106489491	0.0000062129058644	0.0000126929927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8590000000000000	-0.0000062056489492	0.0000062149058828	0.0000127019927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8599999999999999	-0.0000062006489492	0.0000062169058728	0.0000127109927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8610000000000002	-0.0000061956489491	0.0000062189058558	0.0000127199927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8620000000000001	-0.0000061906489492	0.0000062209058813	0.0000127289927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8630000000000000	-0.0000061856489492	0.0000062229058713	0.0000127379927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8639999999999999	-0.0000061806489492	0.0000062249058756	0.0000127469927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8650000000000002	-0.0000061756489492	0.0000062269058656	0.0000127559927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8660000000000001	-0.0000061706489492	0.0000062289058698	0.0000127649927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8670000000000000	-0.0000061656489492	0.0000062309058741	0.0000127739927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8679999999999999	-0.0000061606489492	0.0000062329058783	0.0000127829927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8690000000000002	-0.0000061556489491	0.0000062349058541	0.0000127919927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8700000000000001	-0.0000061506489492	0.0000062369058797	0.0000128009927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8710000000000000	-0.0000061456489492	0.0000062389058697	0.0000128099927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8719999999999999	-0.0000061406489492	0.0000062409058739	0.0000128189927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8730000000000002	-0.0000061356489492	0.0000062429058710	0.0000128279927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8740000000000001	-0.0000061306489492	0.0000062449058753	0.0000128369927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8750000000000000	-0.0000061256489491	0.0000062469058653	0.0000128459927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8759999999999999	-0.0000061206489492	0.0000062489058766	0.0000128549927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8770000000000002	-0.0000061156489492	0.0000062509058738	0.0000128639927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8780000000000001	-0.0000061106489491	0.0000062529058638	0.0000128729927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8790000000000000	-0.0000061056489492	0.0000062549058751	0.0000128819927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8799999999999999	-0.0000061006489492	0.0000062569058723	0.0000128909927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8810000000000002	-0.0000060956489492	0.0000062589058694	0.0000128999927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8820000000000001	-0.0000060906489492	0.0000062609058665	0.0000129089927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8830000000000000	-0.0000060856489492	0.0000062629058850	0.0000129179927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8839999999999999	-0.0000060806489492	0.0000062649058679	0.0000129269927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8850000000000002	-0.0000060756489491	0.0000062669058650	0.0000129359927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8860000000000001	-0.0000060706489492	0.0000062689058692	0.0000129449927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8870000000000000	-0.0000060656489492	0.0000062709058806	0.0000129539927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8879999999999999	-0.0000060606489492	0.0000062729058706	0.0000129629927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8890000000000002	-0.0000060556489491	0.0000062749058606	0.0000129719927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8900000000000001	-0.0000060506489492	0.0000062769058791	0.0000129809927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8910000000000000	-0.0000060456489492	0.0000062789058691	0.0000129899927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8919999999999999	-0.0000060406489492	0.0000062809058733	0.0000129989927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8930000000000002	-0.0000060356489491	0.0000062829058634	0.0000130079927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8940000000000001	-0.0000060306489492	0.0000062849058747	0.0000130169927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8950000000000000	-0.0000060256489492	0.0000062869058789	0.0000130259927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8959999999999999	-0.0000060206489492	0.0000062889058690	0.0000130349927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8970000000000002	-0.0000060156489491	0.0000062909058590	0.0000130439927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8980000000000001	-0.0000060106489492	0.0000062929058774	0.0000130529927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8990000000000000	-0.0000060056489492	0.0000062949058746	0.0000130619927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.8999999999999999	-0.0000060006489492	0.0000062969058717	0.0000130709927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9010000000000002	-0.0000059956489491	0.0000062989058617	0.0000130799927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9020000000000001	-0.0000059906489492	0.0000063009058801	0.0000130889927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9030000000000000	-0.0000059856489492	0.0000063029058702	0.0000130979927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9039999999999999	-0.0000059806489492	0.0000063049058744	0.0000131069927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9050000000000002	-0.0000059756489492	0.0000063069058715	0.0000131159927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9060000000000001	-0.0000059706489492	0.0000063089058687	0.0000131249927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9070000000000000	-0.0000059656489492	0.0000063109058729	0.0000131339927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9079999999999999	-0.0000059606489492	0.0000063129058771	0.0000131429927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9090000000000003	-0.0000059556489491	0.0000063149058601	0.0000131519927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9100000000000001	-0.0000059506489492	0.0000063169058714	0.0000131609927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9110000000000000	-0.0000059456489492	0.0000063189058756	0.0000131699927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9119999999999999	-0.0000059406489492	0.0000063209058728	0.0000131789927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9130000000000003	-0.0000059356489491	0.0000063229058628	0.0000131879927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9140000000000001	-0.0000059306489492	0.0000063249058670	0.0000131969927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9150000000000000	-0.0000059256489492	0.0000063269058855	0.0000132059927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9159999999999999	-0.0000059206489492	0.0000063289058755	0.0000132149927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9170000000000003	-0.0000059156489491	0.0000063309058584	0.0000132239927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9180000000000001	-0.0000059106489492	0.0000063329058768	0.0000132329927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9190000000000000	-0.0000059056489492	0.0000063349058740	0.0000132419927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9199999999999999	-0.0000059006489492	0.0000063369058782	0.0000132509927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9210000000000003	-0.0000058956489491	0.0000063389058611	0.0000132599927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9220000000000002	-0.0000058906489491	0.0000063409058654	0.0000132689927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9230000000000000	-0.0000058856489492	0.0000063429058767	0.0000132779927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9239999999999999	-0.0000058806489492	0.0000063449058738	0.0000132869927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9250000000000003	-0.0000058756489492	0.0000063469058710	0.0000132959927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9260000000000002	-0.0000058706489492	0.0000063489058681	0.0000133049927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9270000000000000	-0.0000058656489492	0.0000063509058723	0.0000133139927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9279999999999999	-0.0000058606489492	0.0000063529058765	0.0000133229927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9290000000000003	-0.0000058556489491	0.0000063549058595	0.0000133319927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9300000000000002	-0.0000058506489492	0.0000063569058779	0.0000133409927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9310000000000000	-0.0000058456489492	0.0000063589058679	0.0000133499927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9319999999999999	-0.0000058406489492	0.0000063609058793	0.0000133589927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9330000000000003	-0.0000058356489491	0.0000063629058622	0.0000133679927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9340000000000002	-0.0000058306489492	0.0000063649058735	0.0000133769927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9350000000000001	-0.0000058256489492	0.0000063669058707	0.0000133859927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9359999999999999	-0.0000058206489492	0.0000063689058749	0.0000133949927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9370000000000003	-0.0000058156489491	0.0000063709058649	0.0000134039927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9380000000000002	-0.0000058106489492	0.0000063729058692	0.0000134129927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9390000000000001	-0.0000058056489492	0.0000063749058805	0.0000134219927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9399999999999999	-0.0000058006489492	0.0000063769058776	0.0000134309927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9410000000000003	-0.0000057956489491	0.0000063789058605	0.0000134399927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9420000000000002	-0.0000057906489492	0.0000063809058719	0.0000134489927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9430000000000001	-0.0000057856489492	0.0000063829058761	0.0000134579927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9440000000000000	-0.0000057806489492	0.0000063849058732	0.0000134669927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9449999999999998	-0.0000057756489492	0.0000063869058704	0.0000134759927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9460000000000002	-0.0000057706489492	0.0000063889058675	0.0000134849927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9470000000000001	-0.0000057656489492	0.0000063909058788	0.0000134939927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9480000000000000	-0.0000057606489491	0.0000063929058618	0.0000135029927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9489999999999998	-0.0000057556489492	0.0000063949058731	0.0000135119927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9500000000000002	-0.0000057506489492	0.0000063969058702	0.0000135209927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9510000000000001	-0.0000057456489492	0.0000063989058674	0.0000135299927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9520000000000000	-0.0000057406489492	0.0000064009058716	0.0000135389927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9529999999999998	-0.0000057356489492	0.0000064029058829	0.0000135479927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9540000000000002	-0.0000057306489491	0.0000064049058587	0.0000135569927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9550000000000001	-0.0000057256489492	0.0000064069058772	0.0000135659927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9560000000000000	-0.0000057206489492	0.0000064089058672	0.0000135749927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9569999999999999	-0.0000057156489492	0.0000064109058785	0.0000135839927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9580000000000002	-0.0000057106489491	0.0000064129058615	0.0000135929927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9590000000000001	-0.0000057056489492	0.0000064149058657	0.0000136019927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9600000000000000	-0.0000057006489492	0.0000064169058841	0.0000136109927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9609999999999999	-0.0000056956489492	0.0000064189058742	0.0000136199927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9620000000000002	-0.0000056906489491	0.0000064209058571	0.0000136289927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9630000000000001	-0.0000056856489492	0.0000064229058755	0.0000136379927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9640000000000000	-0.0000056806489492	0.0000064249058727	0.0000136469927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9649999999999999	-0.0000056756489492	0.0000064269058769	0.0000136559927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9660000000000002	-0.0000056706489491	0.0000064289058598	0.0000136649927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9670000000000001	-0.0000056656489492	0.0000064309058783	0.0000136739927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9680000000000000	-0.0000056606489492	0.0000064329058754	0.0000136829927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9689999999999999	-0.0000056556489492	0.0000064349058725	0.0000136919927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9700000000000002	-0.0000056506489491	0.0000064369058554	0.0000137009927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9710000000000001	-0.0000056456489492	0.0000064389058810	0.0000137099927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9720000000000000	-0.0000056406489492	0.0000064409058710	0.0000137189927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9729999999999999	-0.0000056356489492	0.0000064429058752	0.0000137279927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9740000000000002	-0.0000056306489491	0.0000064449058582	0.0000137369927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9750000000000001	-0.0000056256489492	0.0000064469058766	0.0000137459927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9760000000000000	-0.0000056206489492	0.0000064489058737	0.0000137549927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9769999999999999	-0.0000056156489492	0.0000064509058780	0.0000137639927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9780000000000002	-0.0000056106489491	0.0000064529058609	0.0000137729927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9790000000000001	-0.0000056056489492	0.0000064549058722	0.0000137819927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9800000000000000	-0.0000056006489492	0.0000064569058693	0.0000137909927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9809999999999999	-0.0000055956489492	0.0000064589058807	0.0000137999927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9820000000000002	-0.0000055906489491	0.0000064609058565	0.0000138089927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9830000000000001	-0.0000055856489492	0.0000064629058820	0.0000138179927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9840000000000000	-0.0000055806489491	0.0000064649058650	0.0000138269927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9849999999999999	-0.0000055756489492	0.0000064669058834	0.0000138359927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9860000000000002	-0.0000055706489491	0.0000064689058592	0.0000138449927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9870000000000001	-0.0000055656489492	0.0000064709058706	0.0000138539927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9880000000000000	-0.0000055606489492	0.0000064729058748	0.0000138629927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9889999999999999	-0.0000055556489492	0.0000064749058719	0.0000138719927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9900000000000002	-0.0000055506489491	0.0000064769058620	0.0000138809927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9910000000000001	-0.0000055456489492	0.0000064789058662	0.0000138899927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9920000000000000	-0.0000055406489492	0.0000064809058846	0.0000138989927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9929999999999999	-0.0000055356489492	0.0000064829058747	0.0000139079927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9940000000000002	-0.0000055306489491	0.0000064849058505	0.0000139169927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9950000000000001	-0.0000055256489492	0.0000064869058760	0.0000139259927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9960000000000000	-0.0000055206489492	0.0000064889058874	0.0000139349927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9969999999999999	-0.0000055156489491	0.0000064909058632	0.0000139439927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9980000000000002	-0.0000055106489491	0.0000064929058603	0.0000139529927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+2.9990000000000001	-0.0000055056489492	0.0000064949058787	0.0000139619927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+3.0000000000000000	-0.0000055006489492	0.0000064969058759	0.0000139709927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+3.0009999999999999	-0.0000054956489492	0.0000064989058730	0.0000139799927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+3.0020000000000002	-0.0000054906489491	0.0000065009058630	0.0000139889927221	0.0000000000000000	-0.0000000000000001	0.0000000000000000	
+3.0029999999999997	-0.0000054906489492	0.0000065009058843	0.0000139889927221	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0040000000000000	-0.0000054516883342	0.0000064989058536	0.0000139971809195	0.0000000000000001	-0.0031415926535896	0.0000000000000002	
+3.0049999999999999	-0.0000054127021877	0.0000064969058693	0.0000140052466783	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.0059999999999998	-0.0000053736908942	0.0000064949058678	0.0000140131899188	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0069999999999997	-0.0000053346548388	0.0000064929058775	0.0000140210105628	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0080000000000000	-0.0000052955944068	0.0000064909058631	0.0000140287085330	-0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.0089999999999999	-0.0000052565099838	0.0000064889058674	0.0000140362837535	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.0099999999999998	-0.0000052174019554	0.0000064869058693	0.0000140437361494	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0109999999999997	-0.0000051782707077	0.0000064849058830	0.0000140510656473	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.0120000000000000	-0.0000051391166267	0.0000064829058519	0.0000140582721747	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.0129999999999999	-0.0000050999400991	0.0000064809058685	0.0000140653556606	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0139999999999998	-0.0000050607415114	0.0000064789058690	0.0000140723160351	0.0000000000000000	-0.0031415926535896	-0.0000000000000003	
+3.0149999999999997	-0.0000050215212505	0.0000064769058677	0.0000140791532294	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0160000000000000	-0.0000049822797035	0.0000064749058578	0.0000140858671762	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.0169999999999999	-0.0000049430172578	0.0000064729058819	0.0000140924578090	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.0179999999999998	-0.0000049037343006	0.0000064709058549	0.0000140989250629	-0.0000000000000001	-0.0031415926535898	-0.0000000000000002	
+3.0189999999999997	-0.0000048644312200	0.0000064689058836	0.0000141052688740	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.0200000000000000	-0.0000048251084036	0.0000064669058545	0.0000141114891798	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.0209999999999999	-0.0000047857662397	0.0000064649058741	0.0000141175859188	0.0000000000000000	-0.0031415926535899	-0.0000000000000001	
+3.0219999999999998	-0.0000047464051165	0.0000064629058717	0.0000141235590309	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.0229999999999997	-0.0000047070254224	0.0000064609058687	0.0000141294084571	0.0000000000000000	-0.0031415926535896	0.0000000000000000	
+3.0240000000000000	-0.0000046676275462	0.0000064589058581	0.0000141351341396	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.0249999999999999	-0.0000046282118767	0.0000064569058756	0.0000141407360220	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.0259999999999998	-0.0000045887788028	0.0000064549058644	0.0000141462140490	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.0269999999999997	-0.0000045493287140	0.0000064529058745	0.0000141515681666	0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.0280000000000000	-0.0000045098619992	0.0000064509058633	0.0000141567983218	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0289999999999999	-0.0000044703790484	0.0000064489058736	0.0000141619044630	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.0299999999999998	-0.0000044308802509	0.0000064469058700	0.0000141668865399	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.0309999999999997	-0.0000043913659968	0.0000064449058739	0.0000141717445033	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.0320000000000000	-0.0000043518366758	0.0000064429058572	0.0000141764783053	-0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.0329999999999999	-0.0000043122926784	0.0000064409058695	0.0000141810878990	0.0000000000000002	-0.0031415926535899	0.0000000000000001	
+3.0339999999999998	-0.0000042727343946	0.0000064389058685	0.0000141855732391	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.0349999999999997	-0.0000042331622150	0.0000064369058684	0.0000141899342813	0.0000000000000002	-0.0031415926535899	0.0000000000000000	
+3.0360000000000000	-0.0000041935765300	0.0000064349058552	0.0000141941709824	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.0369999999999999	-0.0000041539777305	0.0000064329058717	0.0000141982833008	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0379999999999998	-0.0000041143662071	0.0000064309058681	0.0000142022711957	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0389999999999997	-0.0000040747423509	0.0000064289058660	0.0000142061346280	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0400000000000000	-0.0000040351065529	0.0000064269058655	0.0000142098735593	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.0409999999999999	-0.0000039954592043	0.0000064249058667	0.0000142134879529	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0419999999999998	-0.0000039558006965	0.0000064229058768	0.0000142169777730	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.0429999999999997	-0.0000039161314207	0.0000064209058747	0.0000142203429852	0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.0440000000000000	-0.0000038764517686	0.0000064189058533	0.0000142235835563	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0449999999999999	-0.0000038367621318	0.0000064169058767	0.0000142266994544	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0459999999999998	-0.0000037970629020	0.0000064149058739	0.0000142296906485	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.0469999999999997	-0.0000037573544710	0.0000064129058594	0.0000142325571094	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.0480000000000000	-0.0000037176372307	0.0000064109058616	0.0000142352988085	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0489999999999999	-0.0000036779115732	0.0000064089058736	0.0000142379157190	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.0499999999999998	-0.0000036381778904	0.0000064069058740	0.0000142404078149	-0.0000000000000001	-0.0031415926535896	-0.0000000000000001	
+3.0509999999999997	-0.0000035984365745	0.0000064049058703	0.0000142427750717	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0520000000000000	-0.0000035586880178	0.0000064029058553	0.0000142450174659	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0529999999999999	-0.0000035189326126	0.0000064009058789	0.0000142471349756	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0539999999999998	-0.0000034791707512	0.0000063989058701	0.0000142491275797	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.0549999999999997	-0.0000034394028261	0.0000063969058647	0.0000142509952586	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.0560000000000000	-0.0000033996292298	0.0000063949058556	0.0000142527379938	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.0569999999999999	-0.0000033598503549	0.0000063929058784	0.0000142543557683	0.0000000000000002	-0.0031415926535896	0.0000000000000000	
+3.0579999999999998	-0.0000033200665938	0.0000063909058764	0.0000142558485659	0.0000000000000002	-0.0031415926535897	-0.0000000000000001	
+3.0589999999999997	-0.0000032802783392	0.0000063889058639	0.0000142572163720	0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.0600000000000001	-0.0000032404859840	0.0000063869058623	0.0000142584591731	0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.0609999999999999	-0.0000032006899208	0.0000063849058718	0.0000142595769568	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0619999999999998	-0.0000031608905423	0.0000063829058711	0.0000142605697123	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.0629999999999997	-0.0000031210882414	0.0000063809058674	0.0000142614374296	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.0639999999999996	-0.0000030812834109	0.0000063789058822	0.0000142621801002	-0.0000000000000001	-0.0031415926535896	0.0000000000000001	
+3.0649999999999999	-0.0000030414764436	0.0000063769058515	0.0000142627977168	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.0659999999999998	-0.0000030016677326	0.0000063749058821	0.0000142632902733	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.0669999999999997	-0.0000029618576705	0.0000063729058675	0.0000142636577648	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.0679999999999996	-0.0000029220466505	0.0000063709058717	0.0000142639001877	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0690000000000000	-0.0000028822350652	0.0000063689058522	0.0000142640175396	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0699999999999998	-0.0000028424233078	0.0000063669058731	0.0000142640098193	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.0709999999999997	-0.0000028026117710	0.0000063649058704	0.0000142638770270	0.0000000000000001	-0.0031415926535899	0.0000000000000002	
+3.0719999999999996	-0.0000027628008480	0.0000063629058727	0.0000142636191639	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.0730000000000000	-0.0000027229909314	0.0000063609058588	0.0000142632362325	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0739999999999998	-0.0000026831824144	0.0000063589058714	0.0000142627282368	-0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0749999999999997	-0.0000026433756897	0.0000063569058750	0.0000142620951816	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0759999999999996	-0.0000026035711502	0.0000063549058697	0.0000142613370732	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.0770000000000000	-0.0000025637691888	0.0000063529058557	0.0000142604539190	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0779999999999998	-0.0000025239701984	0.0000063509058685	0.0000142594457280	0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.0789999999999997	-0.0000024841745717	0.0000063489058798	0.0000142583125099	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0799999999999996	-0.0000024443827014	0.0000063469058755	0.0000142570542759	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0810000000000000	-0.0000024045949803	0.0000063449058557	0.0000142556710385	-0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0819999999999999	-0.0000023648118013	0.0000063429058701	0.0000142541628113	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0829999999999997	-0.0000023250335567	0.0000063409058762	0.0000142525296092	0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.0839999999999996	-0.0000022852606393	0.0000063389058671	0.0000142507714484	-0.0000000000000002	-0.0031415926535899	0.0000000000000000	
+3.0850000000000000	-0.0000022454934415	0.0000063369058640	0.0000142488883461	-0.0000000000000001	-0.0031415926535898	-0.0000000000000002	
+3.0859999999999999	-0.0000022057323560	0.0000063349058671	0.0000142468803210	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.0869999999999997	-0.0000021659777750	0.0000063329058694	0.0000142447473928	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.0879999999999996	-0.0000021262300910	0.0000063309058780	0.0000142424895827	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0890000000000000	-0.0000020864896962	0.0000063289058504	0.0000142401069129	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.0899999999999999	-0.0000020467569829	0.0000063269058648	0.0000142375994070	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0909999999999997	-0.0000020070323433	0.0000063249058715	0.0000142349670896	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0919999999999996	-0.0000019673161693	0.0000063229058706	0.0000142322099868	0.0000000000000003	-0.0031415926535898	0.0000000000000001	
+3.0930000000000000	-0.0000019276088530	0.0000063209058622	0.0000142293281257	0.0000000000000000	-0.0031415926535899	-0.0000000000000001	
+3.0939999999999999	-0.0000018879107863	0.0000063189058748	0.0000142263215349	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0949999999999998	-0.0000018482223610	0.0000063169058801	0.0000142231902439	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.0959999999999996	-0.0000018085439687	0.0000063149058709	0.0000142199342838	0.0000000000000001	-0.0031415926535898	0.0000000000000002	
+3.0970000000000000	-0.0000017688760011	0.0000063129058544	0.0000142165536865	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.0979999999999999	-0.0000017292188497	0.0000063109058806	0.0000142130484856	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.0989999999999998	-0.0000016895729059	0.0000063089058712	0.0000142094187156	0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.0999999999999996	-0.0000016499385610	0.0000063069058761	0.0000142056644122	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1010000000000000	-0.0000016103162061	0.0000063049058527	0.0000142017856126	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1019999999999999	-0.0000015707062324	0.0000063029058792	0.0000141977823551	0.0000000000000002	-0.0031415926535900	0.0000000000000000	
+3.1029999999999998	-0.0000015311090308	0.0000063009058775	0.0000141936546792	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.1039999999999996	-0.0000014915249919	0.0000062989058833	0.0000141894026255	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1050000000000000	-0.0000014519545066	0.0000062969058539	0.0000141850262360	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.1059999999999999	-0.0000014123979654	0.0000062949058676	0.0000141805255541	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1069999999999998	-0.0000013728557587	0.0000062929058675	0.0000141759006240	-0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.1079999999999997	-0.0000013333282767	0.0000062909058751	0.0000141711514915	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.1090000000000000	-0.0000012938159096	0.0000062889058478	0.0000141662782033	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1099999999999999	-0.0000012543190474	0.0000062869058780	0.0000141612808076	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.1109999999999998	-0.0000012148380798	0.0000062849058663	0.0000141561593537	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1119999999999997	-0.0000011753733966	0.0000062829058695	0.0000141509138922	-0.0000000000000001	-0.0031415926535900	-0.0000000000000001	
+3.1130000000000000	-0.0000011359253871	0.0000062809058593	0.0000141455444749	0.0000000000000001	-0.0031415926535900	-0.0000000000000001	
+3.1139999999999999	-0.0000010964944409	0.0000062789058784	0.0000141400511546	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.1149999999999998	-0.0000010570809470	0.0000062769058701	0.0000141344339857	-0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.1159999999999997	-0.0000010176852944	0.0000062749058697	0.0000141286930236	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.1170000000000000	-0.0000009783078719	0.0000062729058633	0.0000141228283249	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.1179999999999999	-0.0000009389490682	0.0000062709058722	0.0000141168399475	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.1189999999999998	-0.0000008996092718	0.0000062689058751	0.0000141107279506	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.1199999999999997	-0.0000008602888709	0.0000062669058720	0.0000141044923944	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.1210000000000000	-0.0000008209882535	0.0000062649058630	0.0000140981333405	0.0000000000000001	-0.0031415926535898	-0.0000000000000002	
+3.1219999999999999	-0.0000007817078076	0.0000062629058694	0.0000140916508517	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1229999999999998	-0.0000007424479209	0.0000062609058771	0.0000140850449919	-0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.1239999999999997	-0.0000007032089808	0.0000062589058649	0.0000140783158263	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1250000000000000	-0.0000006639913746	0.0000062569058610	0.0000140714634213	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1259999999999999	-0.0000006247954893	0.0000062549058657	0.0000140644878447	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.1269999999999998	-0.0000005856217119	0.0000062529058719	0.0000140573891651	0.0000000000000002	-0.0031415926535899	-0.0000000000000001	
+3.1279999999999997	-0.0000005464704289	0.0000062509058724	0.0000140501674528	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1290000000000000	-0.0000005073420267	0.0000062489058531	0.0000140428227788	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1299999999999999	-0.0000004682368916	0.0000062469058779	0.0000140353552159	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1309999999999998	-0.0000004291554095	0.0000062449058759	0.0000140277648376	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1319999999999997	-0.0000003900979660	0.0000062429058685	0.0000140200517188	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.1330000000000000	-0.0000003510649467	0.0000062409058555	0.0000140122159358	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1339999999999999	-0.0000003120567369	0.0000062389058727	0.0000140042575657	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1349999999999998	-0.0000002730737214	0.0000062369058845	0.0000139961766873	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1359999999999997	-0.0000002341162851	0.0000062349058695	0.0000139879733801	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1370000000000000	-0.0000001951848124	0.0000062329058564	0.0000139796477253	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.1379999999999999	-0.0000001562796878	0.0000062309058734	0.0000139711998049	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.1389999999999998	-0.0000001174012949	0.0000062289058710	0.0000139626297023	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1399999999999997	-0.0000000785500176	0.0000062269058703	0.0000139539375022	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.1410000000000000	-0.0000000397262393	0.0000062249058574	0.0000139451232902	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.1419999999999999	-0.0000000009303433	0.0000062229058676	0.0000139361871535	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1429999999999998	0.0000000378372877	0.0000062209058726	0.0000139271291801	0.0000000000000000	-0.0031415926535899	0.0000000000000001	
+3.1439999999999997	0.0000000765762709	0.0000062189058654	0.0000139179494596	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.1450000000000000	0.0000001152862241	0.0000062169058601	0.0000139086480824	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.1459999999999999	0.0000001539667651	0.0000062149058781	0.0000138992251405	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.1469999999999998	0.0000001926175123	0.0000062129058696	0.0000138896807267	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1479999999999997	0.0000002312380841	0.0000062109058774	0.0000138800149354	0.0000000000000000	-0.0031415926535899	-0.0000000000000001	
+3.1490000000000000	0.0000002698280994	0.0000062089058516	0.0000138702278618	-0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.1499999999999999	0.0000003083871773	0.0000062069058777	0.0000138603196026	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.1509999999999998	0.0000003469149373	0.0000062049058773	0.0000138502902556	0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.1519999999999997	0.0000003854109991	0.0000062029058719	0.0000138401399198	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1530000000000000	0.0000004238749827	0.0000062009058615	0.0000138298686953	-0.0000000000000001	-0.0031415926535900	-0.0000000000000001	
+3.1539999999999999	0.0000004623065086	0.0000061989058674	0.0000138194766835	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1549999999999998	0.0000005007051974	0.0000061969058682	0.0000138089639870	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1559999999999997	0.0000005390706702	0.0000061949058712	0.0000137983307096	0.0000000000000000	-0.0031415926535899	-0.0000000000000001	
+3.1570000000000000	0.0000005774025483	0.0000061929058549	0.0000137875769561	0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.1579999999999999	0.0000006157004533	0.0000061909058763	0.0000137767028328	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1589999999999998	0.0000006539640073	0.0000061889058714	0.0000137657084468	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.1599999999999997	0.0000006921928327	0.0000061869058757	0.0000137545939069	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.1610000000000000	0.0000007303865522	0.0000061849058538	0.0000137433593225	-0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.1619999999999999	0.0000007685447888	0.0000061829058624	0.0000137320048048	0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.1629999999999998	0.0000008066671657	0.0000061809058802	0.0000137205304656	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1639999999999997	0.0000008447533071	0.0000061789058646	0.0000137089364182	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.1650000000000000	0.0000008828028367	0.0000061769058654	0.0000136972227772	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.1659999999999999	0.0000009208153790	0.0000061749058755	0.0000136853896580	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.1669999999999998	0.0000009587905591	0.0000061729058734	0.0000136734371774	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.1679999999999997	0.0000009967280020	0.0000061709058735	0.0000136613654535	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.1690000000000000	0.0000010346273333	0.0000061689058544	0.0000136491746054	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1699999999999999	0.0000010724881789	0.0000061669058801	0.0000136368647534	-0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.1709999999999998	0.0000011103101652	0.0000061649058723	0.0000136244360190	-0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.1719999999999997	0.0000011480929190	0.0000061629058738	0.0000136118885248	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.1730000000000000	0.0000011858360673	0.0000061609058560	0.0000135992223946	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.1739999999999999	0.0000012235392375	0.0000061589058688	0.0000135864377537	0.0000000000000000	-0.0031415926535899	-0.0000000000000001	
+3.1749999999999998	0.0000012612020575	0.0000061569058694	0.0000135735347280	0.0000000000000002	-0.0031415926535898	0.0000000000000001	
+3.1759999999999997	0.0000012988241558	0.0000061549058721	0.0000135605134449	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.1770000000000000	0.0000013364051609	0.0000061529058555	0.0000135473740329	-0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.1779999999999999	0.0000013739447019	0.0000061509058765	0.0000135341166219	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1789999999999998	0.0000014114424084	0.0000061489058783	0.0000135207413424	-0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.1799999999999997	0.0000014488979102	0.0000061469058820	0.0000135072483267	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.1810000000000000	0.0000014863108378	0.0000061449058451	0.0000134936377077	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1819999999999999	0.0000015236808216	0.0000061429058741	0.0000134799096200	0.0000000000000002	-0.0031415926535897	0.0000000000000001	
+3.1829999999999998	0.0000015610074931	0.0000061409058696	0.0000134660641989	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1839999999999997	0.0000015982904838	0.0000061389058741	0.0000134521015812	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.1850000000000001	0.0000016355294258	0.0000061369058522	0.0000134380219046	-0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.1859999999999999	0.0000016727239514	0.0000061349058676	0.0000134238253081	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1869999999999998	0.0000017098736936	0.0000061329058850	0.0000134095119318	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1879999999999997	0.0000017469782858	0.0000061309058686	0.0000133950819169	0.0000000000000001	-0.0031415926535900	0.0000000000000001	
+3.1890000000000001	0.0000017840373618	0.0000061289058541	0.0000133805354059	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.1899999999999999	0.0000018210505557	0.0000061269058770	0.0000133658725424	-0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.1909999999999998	0.0000018580175023	0.0000061249058661	0.0000133510934710	0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.1919999999999997	0.0000018949378367	0.0000061229058712	0.0000133361983377	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1929999999999996	0.0000019318111945	0.0000061209058780	0.0000133211872895	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.1940000000000000	0.0000019686372119	0.0000061189058651	0.0000133060604744	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1949999999999998	0.0000020054155254	0.0000061169058682	0.0000132908180418	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.1959999999999997	0.0000020421457719	0.0000061149058729	0.0000132754601422	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.1969999999999996	0.0000020788275889	0.0000061129058721	0.0000132599869270	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.1980000000000000	0.0000021154606146	0.0000061109058515	0.0000132443985491	-0.0000000000000002	-0.0031415926535898	0.0000000000000001	
+3.1989999999999998	0.0000021520444871	0.0000061089058752	0.0000132286951623	-0.0000000000000000	-0.0031415926535899	0.0000000000000001	
+3.1999999999999997	0.0000021885788456	0.0000061069058719	0.0000132128769215	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2009999999999996	0.0000022250633293	0.0000061049058771	0.0000131969439829	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.2020000000000000	0.0000022614975784	0.0000061029058554	0.0000131808965036	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2029999999999998	0.0000022978812330	0.0000061009058777	0.0000131647346423	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2039999999999997	0.0000023342139343	0.0000060989058730	0.0000131484585582	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2049999999999996	0.0000023704953234	0.0000060969058766	0.0000131320684121	-0.0000000000000000	-0.0031415926535899	0.0000000000000001	
+3.2060000000000000	0.0000024067250425	0.0000060949058602	0.0000131155643657	-0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.2069999999999999	0.0000024429027339	0.0000060929058593	0.0000130989465820	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2079999999999997	0.0000024790280405	0.0000060909058737	0.0000130822152248	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.2089999999999996	0.0000025151006058	0.0000060889058751	0.0000130653704595	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.2100000000000000	0.0000025511200739	0.0000060869058492	0.0000130484124520	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2109999999999999	0.0000025870860891	0.0000060849058669	0.0000130313413701	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.2119999999999997	0.0000026229982964	0.0000060829058786	0.0000130141573819	0.0000000000000000	-0.0031415926535899	0.0000000000000001	
+3.2129999999999996	0.0000026588563417	0.0000060809058627	0.0000129968606572	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.2140000000000000	0.0000026946598708	0.0000060789058549	0.0000129794513667	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2149999999999999	0.0000027304085303	0.0000060769058693	0.0000129619296822	-0.0000000000000002	-0.0031415926535899	-0.0000000000000001	
+3.2159999999999997	0.0000027661019676	0.0000060749058773	0.0000129442957766	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.2169999999999996	0.0000028017398302	0.0000060729058719	0.0000129265498240	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.2180000000000000	0.0000028373217666	0.0000060709058601	0.0000129086919994	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2189999999999999	0.0000028728474254	0.0000060689058703	0.0000128907224793	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.2199999999999998	0.0000029083164561	0.0000060669058740	0.0000128726414408	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2209999999999996	0.0000029437285086	0.0000060649058710	0.0000128544490625	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.2220000000000000	0.0000029790832334	0.0000060629058686	0.0000128361455239	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.2229999999999999	0.0000030143802816	0.0000060609058737	0.0000128177310057	0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.2239999999999998	0.0000030496193047	0.0000060589058720	0.0000127992056896	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2249999999999996	0.0000030847999551	0.0000060569058707	0.0000127805697584	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.2260000000000000	0.0000031199218855	0.0000060549058553	0.0000127618233961	-0.0000000000000000	-0.0031415926535899	0.0000000000000001	
+3.2269999999999999	0.0000031549847491	0.0000060529058757	0.0000127429667878	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.2279999999999998	0.0000031899882001	0.0000060509058678	0.0000127240001193	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2289999999999996	0.0000032249318929	0.0000060489058670	0.0000127049235781	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.2300000000000000	0.0000032598154827	0.0000060469058450	0.0000126857373523	-0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.2309999999999999	0.0000032946386250	0.0000060449058725	0.0000126664416315	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.2319999999999998	0.0000033294009763	0.0000060429058786	0.0000126470366059	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.2329999999999997	0.0000033641021935	0.0000060409058632	0.0000126275224670	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2340000000000000	0.0000033987419341	0.0000060389058688	0.0000126078994076	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2349999999999999	0.0000034333198562	0.0000060369058812	0.0000125881676212	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.2359999999999998	0.0000034678356185	0.0000060349058718	0.0000125683273026	-0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.2369999999999997	0.0000035022888804	0.0000060329058762	0.0000125483786476	-0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.2380000000000000	0.0000035366793019	0.0000060309058586	0.0000125283218531	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.2389999999999999	0.0000035710065434	0.0000060289058689	0.0000125081571172	0.0000000000000002	-0.0031415926535897	0.0000000000000002	
+3.2399999999999998	0.0000036052702662	0.0000060269058784	0.0000124878846387	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2409999999999997	0.0000036394701323	0.0000060249058730	0.0000124675046177	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.2420000000000000	0.0000036736058039	0.0000060229058595	0.0000124470172554	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.2429999999999999	0.0000037076769443	0.0000060209058665	0.0000124264227540	-0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.2439999999999998	0.0000037416832170	0.0000060189058724	0.0000124057213169	0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.2449999999999997	0.0000037756242866	0.0000060169058701	0.0000123849131481	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2460000000000000	0.0000038094998180	0.0000060149058595	0.0000123639984532	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2469999999999999	0.0000038433094769	0.0000060129058690	0.0000123429774386	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.2479999999999998	0.0000038770529296	0.0000060109058700	0.0000123218503117	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2489999999999997	0.0000039107298431	0.0000060089058767	0.0000123006172811	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.2500000000000000	0.0000039443398849	0.0000060069058677	0.0000122792785563	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2509999999999999	0.0000039778827235	0.0000060049058642	0.0000122578343479	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2519999999999998	0.0000040113580276	0.0000060029058803	0.0000122362848675	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2529999999999997	0.0000040447654669	0.0000060009058733	0.0000122146303279	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.2540000000000000	0.0000040781047119	0.0000059989058574	0.0000121928709428	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.2549999999999999	0.0000041113754332	0.0000059969058679	0.0000121710069269	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2559999999999998	0.0000041445773026	0.0000059949058693	0.0000121490384960	0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.2569999999999997	0.0000041777099924	0.0000059929058827	0.0000121269658669	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2580000000000000	0.0000042107731757	0.0000059909058585	0.0000121047892575	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2589999999999999	0.0000042437665260	0.0000059889058674	0.0000120825088867	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.2599999999999998	0.0000042766897178	0.0000059869058668	0.0000120601249743	0.0000000000000000	-0.0031415926535900	-0.0000000000000001	
+3.2609999999999997	0.0000043095424261	0.0000059849058708	0.0000120376377413	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.2620000000000000	0.0000043423243267	0.0000059829058580	0.0000120150474096	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2629999999999999	0.0000043750350959	0.0000059809058709	0.0000119923542022	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.2639999999999998	0.0000044076744111	0.0000059789058811	0.0000119695583430	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2649999999999997	0.0000044402419500	0.0000059769058670	0.0000119466600571	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2660000000000000	0.0000044727373913	0.0000059749058641	0.0000119236595703	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.2669999999999999	0.0000045051604141	0.0000059729058653	0.0000119005571098	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2679999999999998	0.0000045375106985	0.0000059709058703	0.0000118773529036	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.2689999999999997	0.0000045697879252	0.0000059689058792	0.0000118540471806	-0.0000000000000000	-0.0031415926535897	0.0000000000000001	
+3.2700000000000000	0.0000046019917758	0.0000059669058491	0.0000118306401708	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2709999999999999	0.0000046341219321	0.0000059649058653	0.0000118071321055	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2719999999999998	0.0000046661780773	0.0000059629058779	0.0000117835232164	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.2729999999999997	0.0000046981598949	0.0000059609058796	0.0000117598137366	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2740000000000000	0.0000047300670694	0.0000059589058562	0.0000117360039001	-0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.2749999999999999	0.0000047618992856	0.0000059569058715	0.0000117120939420	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2759999999999998	0.0000047936562296	0.0000059549058685	0.0000116880840981	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.2769999999999997	0.0000048253375877	0.0000059529058756	0.0000116639746056	-0.0000000000000000	-0.0031415926535899	0.0000000000000001	
+3.2780000000000000	0.0000048569430476	0.0000059509058500	0.0000116397657021	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2789999999999999	0.0000048884722970	0.0000059489058769	0.0000116154576270	0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2799999999999998	0.0000049199250249	0.0000059469058709	0.0000115910506198	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2809999999999997	0.0000049513009208	0.0000059449058674	0.0000115665449216	-0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.2820000000000000	0.0000049825996751	0.0000059429058591	0.0000115419407742	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.2829999999999999	0.0000050138209789	0.0000059409058745	0.0000115172384204	-0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.2839999999999998	0.0000050449645240	0.0000059389058706	0.0000114924381041	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2849999999999997	0.0000050760300030	0.0000059369058760	0.0000114675400700	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.2860000000000000	0.0000051070171094	0.0000059349058548	0.0000114425445638	0.0000000000000000	-0.0031415926535899	-0.0000000000000001	
+3.2869999999999999	0.0000051379255373	0.0000059329058638	0.0000114174518323	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.2879999999999998	0.0000051687549816	0.0000059309058746	0.0000113922621231	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.2889999999999997	0.0000051995051382	0.0000059289058726	0.0000113669756848	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2900000000000000	0.0000052301757035	0.0000059269058579	0.0000113415927670	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.2909999999999999	0.0000052607663747	0.0000059249058659	0.0000113161136201	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.2919999999999998	0.0000052912768500	0.0000059229058821	0.0000112905384958	0.0000000000000002	-0.0031415926535897	0.0000000000000001	
+3.2929999999999997	0.0000053217068283	0.0000059209058710	0.0000112648676463	-0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.2940000000000000	0.0000053520560092	0.0000059189058608	0.0000112391013250	-0.0000000000000002	-0.0031415926535899	-0.0000000000000001	
+3.2949999999999999	0.0000053823240931	0.0000059169058727	0.0000112132397864	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.2959999999999998	0.0000054125107814	0.0000059149058711	0.0000111872832854	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.2969999999999997	0.0000054426157761	0.0000059129058772	0.0000111612320785	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.2980000000000000	0.0000054726387801	0.0000059109058553	0.0000111350864226	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.2989999999999999	0.0000055025794971	0.0000059089058762	0.0000111088465759	0.0000000000000002	-0.0031415926535898	0.0000000000000001	
+3.2999999999999998	0.0000055324376316	0.0000059069058690	0.0000110825127973	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.3009999999999997	0.0000055622128888	0.0000059049058760	0.0000110560853467	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.3020000000000000	0.0000055919049750	0.0000059029058544	0.0000110295644848	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3029999999999999	0.0000056215135970	0.0000059009058753	0.0000110029504737	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3039999999999998	0.0000056510384627	0.0000058989058744	0.0000109762435758	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3049999999999997	0.0000056804792806	0.0000058969058731	0.0000109494440547	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3060000000000000	0.0000057098357602	0.0000058949058498	0.0000109225521749	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3069999999999999	0.0000057391076117	0.0000058929058754	0.0000108955682019	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.3079999999999998	0.0000057682945463	0.0000058909058718	0.0000108684924020	0.0000000000000001	-0.0031415926535899	0.0000000000000001	
+3.3089999999999997	0.0000057973962758	0.0000058889058670	0.0000108413250424	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.3100000000000001	0.0000058264125131	0.0000058869058610	0.0000108140663912	-0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.3109999999999999	0.0000058553429718	0.0000058849058751	0.0000107867167176	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.3119999999999998	0.0000058841873663	0.0000058829058663	0.0000107592762912	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3129999999999997	0.0000059129454120	0.0000058809058772	0.0000107317453832	0.0000000000000000	-0.0031415926535897	-0.0000000000000001	
+3.3140000000000001	0.0000059416168250	0.0000058789058508	0.0000107041242650	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.3149999999999999	0.0000059702013223	0.0000058769058722	0.0000106764132095	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.3159999999999998	0.0000059986986219	0.0000058749058774	0.0000106486124899	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3169999999999997	0.0000060271084425	0.0000058729058661	0.0000106207223808	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3179999999999996	0.0000060554305036	0.0000058709058738	0.0000105927431574	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.3190000000000000	0.0000060836645259	0.0000058689058577	0.0000105646750958	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.3199999999999998	0.0000061118102305	0.0000058669058673	0.0000105365184731	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3209999999999997	0.0000061398673397	0.0000058649058741	0.0000105082735672	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.3219999999999996	0.0000061678355766	0.0000058629058709	0.0000104799406568	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3230000000000000	0.0000061957146652	0.0000058609058575	0.0000104515200215	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3239999999999998	0.0000062235043303	0.0000058589058692	0.0000104230119419	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3249999999999997	0.0000062512042976	0.0000058569058775	0.0000103944166993	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3259999999999996	0.0000062788142938	0.0000058549058680	0.0000103657345759	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3270000000000000	0.0000063063340464	0.0000058529058548	0.0000103369658548	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3279999999999998	0.0000063337632836	0.0000058509058661	0.0000103081108200	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3289999999999997	0.0000063611017349	0.0000058489058734	0.0000102791697563	0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3299999999999996	0.0000063883491304	0.0000058469058765	0.0000102501429493	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.3310000000000000	0.0000064155052013	0.0000058449058468	0.0000102210306853	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3319999999999999	0.0000064425696793	0.0000058429058694	0.0000101918332520	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3329999999999997	0.0000064695422975	0.0000058409058802	0.0000101625509372	-0.0000000000000001	-0.0031415926535897	-0.0000000000000001	
+3.3339999999999996	0.0000064964227897	0.0000058389058649	0.0000101331840301	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3350000000000000	0.0000065232108905	0.0000058369058588	0.0000101037328205	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3359999999999999	0.0000065499063355	0.0000058349058760	0.0000100741975992	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3369999999999997	0.0000065765088614	0.0000058329058736	0.0000100445786574	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.3379999999999996	0.0000066030182054	0.0000058309058728	0.0000100148762877	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3390000000000000	0.0000066294341061	0.0000058289058593	0.0000099850907831	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3399999999999999	0.0000066557563026	0.0000058269058612	0.0000099552224376	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.3409999999999997	0.0000066819845352	0.0000058249058785	0.0000099252715461	-0.0000000000000001	-0.0031415926535899	-0.0000000000000000	
+3.3419999999999996	0.0000067081185451	0.0000058229058683	0.0000098952384040	0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.3430000000000000	0.0000067341580742	0.0000058209058588	0.0000098651233079	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.3439999999999999	0.0000067601028656	0.0000058189058713	0.0000098349265550	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.3449999999999998	0.0000067859526632	0.0000058169058700	0.0000098046484432	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.3459999999999996	0.0000068117072120	0.0000058149058760	0.0000097742892715	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.3470000000000000	0.0000068373662576	0.0000058129058609	0.0000097438493393	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.3479999999999999	0.0000068629295469	0.0000058109058669	0.0000097133289473	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3489999999999998	0.0000068883968276	0.0000058089058727	0.0000096827283966	-0.0000000000000000	-0.0031415926535899	0.0000000000000000	
+3.3499999999999996	0.0000069137678483	0.0000058069058709	0.0000096520479892	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3510000000000000	0.0000069390423587	0.0000058049058614	0.0000096212880279	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3519999999999999	0.0000069642201091	0.0000058029058725	0.0000095904488164	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.3529999999999998	0.0000069893008513	0.0000058009058684	0.0000095595306589	0.0000000000000002	-0.0031415926535898	0.0000000000000001	
+3.3539999999999996	0.0000070142843376	0.0000057989058702	0.0000095285338606	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.3550000000000000	0.0000070391703215	0.0000057969058565	0.0000094974587274	-0.0000000000000001	-0.0031415926535898	-0.0000000000000001	
+3.3559999999999999	0.0000070639585572	0.0000057949058768	0.0000094663055662	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3569999999999998	0.0000070886488003	0.0000057929058670	0.0000094350746843	0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.3579999999999997	0.0000071132408070	0.0000057909058766	0.0000094037663899	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3590000000000000	0.0000071377343346	0.0000057889058558	0.0000093723809920	-0.0000000000000001	-0.0031415926535899	-0.0000000000000001	
+3.3599999999999999	0.0000071621291414	0.0000057869058753	0.0000093409188006	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3609999999999998	0.0000071864249865	0.0000057849058640	0.0000093093801259	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.3619999999999997	0.0000072106216302	0.0000057829058785	0.0000092777652794	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3630000000000000	0.0000072347188338	0.0000057809058619	0.0000092460745730	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3639999999999999	0.0000072587163593	0.0000057789058706	0.0000092143083195	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3649999999999998	0.0000072826139699	0.0000057769058691	0.0000091824668324	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3659999999999997	0.0000073064114297	0.0000057749058713	0.0000091505504261	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3670000000000000	0.0000073301085040	0.0000057729058629	0.0000091185594154	-0.0000000000000002	-0.0031415926535898	-0.0000000000000001	
+3.3679999999999999	0.0000073537049587	0.0000057709058720	0.0000090864941162	0.0000000000000001	-0.0031415926535897	-0.0000000000000000	
+3.3689999999999998	0.0000073772005610	0.0000057689058702	0.0000090543548449	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3699999999999997	0.0000074005950791	0.0000057669058784	0.0000090221419187	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.3710000000000000	0.0000074238882820	0.0000057649058539	0.0000089898556555	-0.0000000000000000	-0.0031415926535898	0.0000000000000001	
+3.3719999999999999	0.0000074470799399	0.0000057629058675	0.0000089574963741	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3729999999999998	0.0000074701698237	0.0000057609058764	0.0000089250643937	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.3739999999999997	0.0000074931577057	0.0000057589058733	0.0000088925600344	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3750000000000000	0.0000075160433591	0.0000057569058509	0.0000088599836171	0.0000000000000001	-0.0031415926535897	-0.0000000000000000	
+3.3759999999999999	0.0000075388265577	0.0000057549058730	0.0000088273354633	0.0000000000000001	-0.0031415926535898	0.0000000000000001	
+3.3769999999999998	0.0000075615070770	0.0000057529058682	0.0000087946158952	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3779999999999997	0.0000075840846929	0.0000057509058720	0.0000087618252357	0.0000000000000000	-0.0031415926535898	-0.0000000000000001	
+3.3790000000000000	0.0000076065591827	0.0000057489058557	0.0000087289638084	0.0000000000000002	-0.0031415926535899	0.0000000000000001	
+3.3799999999999999	0.0000076289303245	0.0000057469058760	0.0000086960319379	0.0000000000000001	-0.0031415926535897	0.0000000000000001	
+3.3809999999999998	0.0000076511978976	0.0000057449058758	0.0000086630299488	0.0000000000000000	-0.0031415926535897	-0.0000000000000000	
+3.3819999999999997	0.0000076733616821	0.0000057429058761	0.0000086299581671	0.0000000000000001	-0.0031415926535899	0.0000000000000000	
+3.3830000000000000	0.0000076954214594	0.0000057409058556	0.0000085968169191	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.3839999999999999	0.0000077173770117	0.0000057389058780	0.0000085636065320	0.0000000000000002	-0.0031415926535898	0.0000000000000001	
+3.3849999999999998	0.0000077392281223	0.0000057369058648	0.0000085303273335	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3859999999999997	0.0000077609745756	0.0000057349058799	0.0000084969796520	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3870000000000000	0.0000077826161569	0.0000057329058590	0.0000084635638166	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3879999999999999	0.0000078041526526	0.0000057309058660	0.0000084300801573	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.3889999999999998	0.0000078255838502	0.0000057289058793	0.0000083965290045	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.3899999999999997	0.0000078469095382	0.0000057269058702	0.0000083629106892	0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.3910000000000000	0.0000078681295060	0.0000057249058528	0.0000083292255432	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3919999999999999	0.0000078892435443	0.0000057229058837	0.0000082954738992	-0.0000000000000002	-0.0031415926535898	-0.0000000000000000	
+3.3929999999999998	0.0000079102514447	0.0000057209058704	0.0000082616560901	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.3939999999999997	0.0000079311529997	0.0000057189058694	0.0000082277724497	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3950000000000000	0.0000079519480033	0.0000057169058521	0.0000081938233124	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.3959999999999999	0.0000079726362500	0.0000057149058752	0.0000081598090135	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3969999999999998	0.0000079932175357	0.0000057129058674	0.0000081257298883	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3979999999999997	0.0000080136916573	0.0000057109058782	0.0000080915862735	-0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.3990000000000000	0.0000080340584127	0.0000057089058576	0.0000080573785059	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.3999999999999999	0.0000080543176009	0.0000057069058766	0.0000080231069232	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.4009999999999998	0.0000080744690220	0.0000057049058709	0.0000079887718636	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.4019999999999997	0.0000080945124771	0.0000057029058688	0.0000079543736659	-0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.4030000000000000	0.0000081144477682	0.0000057009058557	0.0000079199126697	-0.0000000000000002	-0.0031415926535898	-0.0000000000000000	
+3.4039999999999999	0.0000081342746988	0.0000056989058671	0.0000078853892152	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4049999999999998	0.0000081539930731	0.0000056969058743	0.0000078508036430	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4059999999999997	0.0000081736026964	0.0000056949058770	0.0000078161562945	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4070000000000000	0.0000081931033754	0.0000056929058467	0.0000077814475114	0.0000000000000000	-0.0031415926535897	0.0000000000000000	
+3.4079999999999999	0.0000082124949173	0.0000056909058683	0.0000077466776368	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4089999999999998	0.0000082317771310	0.0000056889058778	0.0000077118470134	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4099999999999997	0.0000082509498262	0.0000056869058605	0.0000076769559851	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4110000000000000	0.0000082700128134	0.0000056849058591	0.0000076420048963	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4119999999999999	0.0000082889659047	0.0000056829058803	0.0000076069940921	0.0000000000000001	-0.0031415926535897	0.0000000000000000	
+3.4129999999999998	0.0000083078089130	0.0000056809058672	0.0000075719239177	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4139999999999997	0.0000083265416522	0.0000056789058762	0.0000075367947194	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4150000000000000	0.0000083451639376	0.0000056769058646	0.0000075016068440	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4159999999999999	0.0000083636755853	0.0000056749058676	0.0000074663606386	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4169999999999998	0.0000083820764126	0.0000056729058850	0.0000074310564513	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4179999999999997	0.0000084003662379	0.0000056709058669	0.0000073956946303	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4190000000000000	0.0000084185448807	0.0000056689058628	0.0000073602755248	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4199999999999999	0.0000084366121615	0.0000056669058724	0.0000073247994843	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4209999999999998	0.0000084545679021	0.0000056649058671	0.0000072892668588	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4219999999999997	0.0000084724119253	0.0000056629058679	0.0000072536779992	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.4230000000000000	0.0000084901440549	0.0000056609058605	0.0000072180332567	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4239999999999999	0.0000085077641159	0.0000056589058730	0.0000071823329830	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4249999999999998	0.0000085252719344	0.0000056569058697	0.0000071465775305	0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4259999999999997	0.0000085426673376	0.0000056549058716	0.0000071107672522	-0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.4270000000000000	0.0000085599501539	0.0000056529058572	0.0000070749025013	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4279999999999999	0.0000085771202126	0.0000056509058689	0.0000070389836320	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4289999999999998	0.0000085941773443	0.0000056489058780	0.0000070030109987	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4299999999999997	0.0000086111213807	0.0000056469058772	0.0000069669849565	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4310000000000000	0.0000086279521545	0.0000056449058591	0.0000069309058607	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4319999999999999	0.0000086446694996	0.0000056429058733	0.0000068947740678	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4329999999999998	0.0000086612732510	0.0000056409058769	0.0000068585899342	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4339999999999997	0.0000086777632449	0.0000056389058696	0.0000068223538169	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4350000000000001	0.0000086941393185	0.0000056369058583	0.0000067860660737	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4359999999999999	0.0000087104013101	0.0000056349058641	0.0000067497270627	0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4369999999999998	0.0000087265490593	0.0000056329058796	0.0000067133371427	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4379999999999997	0.0000087425824067	0.0000056309058691	0.0000066768966725	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4390000000000001	0.0000087585011940	0.0000056289058536	0.0000066404060120	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4399999999999999	0.0000087743052642	0.0000056269058827	0.0000066038655215	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4409999999999998	0.0000087899944613	0.0000056249058637	0.0000065672755613	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4419999999999997	0.0000088055686303	0.0000056229058745	0.0000065306364927	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4430000000000001	0.0000088210276177	0.0000056209058580	0.0000064939486772	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4440000000000000	0.0000088363712708	0.0000056189058710	0.0000064572124771	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4449999999999998	0.0000088515994382	0.0000056169058703	0.0000064204282549	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4459999999999997	0.0000088667119696	0.0000056149058701	0.0000063835963735	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4469999999999996	0.0000088817087158	0.0000056129058843	0.0000063467171966	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4480000000000000	0.0000088965895289	0.0000056109058559	0.0000063097910880	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4489999999999998	0.0000089113542620	0.0000056089058626	0.0000062728184123	0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.4499999999999997	0.0000089260027692	0.0000056069058758	0.0000062357995344	-0.0000000000000002	-0.0031415926535898	0.0000000000000000	
+3.4509999999999996	0.0000089405349062	0.0000056049058670	0.0000061987348195	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4520000000000000	0.0000089549505294	0.0000056029058571	0.0000061616246336	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4529999999999998	0.0000089692494965	0.0000056009058813	0.0000061244693429	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4539999999999997	0.0000089834316665	0.0000055989058685	0.0000060872693141	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4549999999999996	0.0000089974968994	0.0000055969058752	0.0000060500249143	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4560000000000000	0.0000090114450563	0.0000055949058514	0.0000060127365111	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4569999999999999	0.0000090252759997	0.0000055929058609	0.0000059754044726	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4579999999999997	0.0000090389895928	0.0000055909058819	0.0000059380291673	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4589999999999996	0.0000090525857006	0.0000055889058788	0.0000059006109639	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4600000000000000	0.0000090660641887	0.0000055869058513	0.0000058631502317	-0.0000000000000002	-0.0031415926535898	-0.0000000000000000	
+3.4609999999999999	0.0000090794249240	0.0000055849058773	0.0000058256473407	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4619999999999997	0.0000090926677749	0.0000055829058712	0.0000057881026608	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4629999999999996	0.0000091057926105	0.0000055809058756	0.0000057505165625	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4640000000000000	0.0000091187993013	0.0000055789058616	0.0000057128894169	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4649999999999999	0.0000091316877190	0.0000055769058645	0.0000056752215954	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4659999999999997	0.0000091444577363	0.0000055749058770	0.0000056375134697	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4669999999999996	0.0000091571092272	0.0000055729058775	0.0000055997654119	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4680000000000000	0.0000091696420668	0.0000055709058587	0.0000055619777945	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4689999999999999	0.0000091820561315	0.0000055689058700	0.0000055241509907	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4699999999999998	0.0000091943512987	0.0000055669058827	0.0000054862853737	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4709999999999996	0.0000092065274471	0.0000055649058681	0.0000054483813172	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4720000000000000	0.0000092185844565	0.0000055629058616	0.0000054104391952	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4729999999999999	0.0000092305222079	0.0000055609058628	0.0000053724593824	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4739999999999998	0.0000092423405835	0.0000055589058715	0.0000053344422536	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4749999999999996	0.0000092540394667	0.0000055569058732	0.0000052963881838	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4760000000000000	0.0000092656187419	0.0000055549058464	0.0000052582975487	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4769999999999999	0.0000092770782949	0.0000055529058688	0.0000052201707245	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4779999999999998	0.0000092884180126	0.0000055509058693	0.0000051820080871	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4789999999999996	0.0000092996377831	0.0000055489058759	0.0000051438100133	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4800000000000000	0.0000093107374956	0.0000055469058672	0.0000051055768801	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4809999999999999	0.0000093217170406	0.0000055449058711	0.0000050673090649	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4819999999999998	0.0000093325763098	0.0000055429058733	0.0000050290069453	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4829999999999997	0.0000093433151959	0.0000055409058735	0.0000049906708994	0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4840000000000000	0.0000093539335929	0.0000055389058501	0.0000049523013055	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4849999999999999	0.0000093644313962	0.0000055369058667	0.0000049138985424	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4859999999999998	0.0000093748085020	0.0000055349058735	0.0000048754629890	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4869999999999997	0.0000093850648079	0.0000055329058771	0.0000048369950247	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4880000000000000	0.0000093952002127	0.0000055309058560	0.0000047984950290	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4889999999999999	0.0000094052146164	0.0000055289058740	0.0000047599633823	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4899999999999998	0.0000094151079202	0.0000055269058738	0.0000047214004644	0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4909999999999997	0.0000094248800263	0.0000055249058766	0.0000046828066562	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4920000000000000	0.0000094345308384	0.0000055229058606	0.0000046441823385	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4929999999999999	0.0000094440602612	0.0000055209058684	0.0000046055278926	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4939999999999998	0.0000094534682007	0.0000055189058712	0.0000045668436999	-0.0000000000000000	-0.0031415926535898	-0.0000000000000000	
+3.4949999999999997	0.0000094627545639	0.0000055169058687	0.0000045281301422	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4960000000000000	0.0000094719192593	0.0000055149058606	0.0000044893876016	-0.0000000000000001	-0.0031415926535898	0.0000000000000000	
+3.4969999999999999	0.0000094809621964	0.0000055129058680	0.0000044506164606	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.4979999999999998	0.0000094898832860	0.0000055109058836	0.0000044118171017	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.4989999999999997	0.0000094986824399	0.0000055089058714	0.0000043729899079	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.5000000000000000	0.0000095073595714	0.0000055069058597	0.0000043341352623	-0.0000000000000000	-0.0031415926535898	0.0000000000000000	
+3.5009999999999999	0.0000095159145948	0.0000055049058765	0.0000042952535486	-0.0000000000000001	-0.0031415926535898	-0.0000000000000000	
+3.5019999999999998	0.0000095243474256	0.0000055029058791	0.0000042563451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5029999999999997	0.0000095193474256	0.0000055009058779	0.0000042473451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5040000000000000	0.0000095143474256	0.0000054989058697	0.0000042383451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5049999999999999	0.0000095093474256	0.0000054969058686	0.0000042293451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5059999999999998	0.0000095043474256	0.0000054949058816	0.0000042203451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5069999999999997	0.0000094993474256	0.0000054929058734	0.0000042113451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5080000000000000	0.0000094943474256	0.0000054909058652	0.0000042023451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5089999999999999	0.0000094893474256	0.0000054889058782	0.0000041933451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5099999999999998	0.0000094843474256	0.0000054869058771	0.0000041843451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5109999999999997	0.0000094793474256	0.0000054849058688	0.0000041753451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5120000000000000	0.0000094743474256	0.0000054829058677	0.0000041663451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5129999999999999	0.0000094693474256	0.0000054809058737	0.0000041573451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5139999999999998	0.0000094643474256	0.0000054789058796	0.0000041483451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5149999999999997	0.0000094593474256	0.0000054769058714	0.0000041393451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5160000000000000	0.0000094543474256	0.0000054749058561	0.0000041303451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5169999999999999	0.0000094493474256	0.0000054729058691	0.0000041213451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5179999999999998	0.0000094443474256	0.0000054709058822	0.0000041123451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5189999999999997	0.0000094393474256	0.0000054689058740	0.0000041033451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5200000000000000	0.0000094343474256	0.0000054669058586	0.0000040943451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5209999999999999	0.0000094293474256	0.0000054649058717	0.0000040853451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5219999999999998	0.0000094243474256	0.0000054629058705	0.0000040763451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5229999999999997	0.0000094193474256	0.0000054609058694	0.0000040673451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5240000000000000	0.0000094143474256	0.0000054589058683	0.0000040583451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5249999999999999	0.0000094093474256	0.0000054569058742	0.0000040493451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5259999999999998	0.0000094043474256	0.0000054549058802	0.0000040403451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5269999999999997	0.0000093993474256	0.0000054529058791	0.0000040313451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5280000000000000	0.0000093943474256	0.0000054509058637	0.0000040223451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5289999999999999	0.0000093893474256	0.0000054489058839	0.0000040133451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5299999999999998	0.0000093843474256	0.0000054469058756	0.0000040043451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5309999999999997	0.0000093793474256	0.0000054449058745	0.0000039953451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5320000000000000	0.0000093743474256	0.0000054429058663	0.0000039863451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5329999999999999	0.0000093693474256	0.0000054409058651	0.0000039773451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5339999999999998	0.0000093643474256	0.0000054389058782	0.0000039683451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5349999999999997	0.0000093593474256	0.0000054369058842	0.0000039593451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5360000000000000	0.0000093543474256	0.0000054349058546	0.0000039503451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5369999999999999	0.0000093493474256	0.0000054329058819	0.0000039413451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5379999999999998	0.0000093443474256	0.0000054309058665	0.0000039323451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5389999999999997	0.0000093393474256	0.0000054289058796	0.0000039233451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5400000000000000	0.0000093343474256	0.0000054269058572	0.0000039143451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5409999999999999	0.0000093293474256	0.0000054249058773	0.0000039053451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5419999999999998	0.0000093243474256	0.0000054229058762	0.0000038963451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5429999999999997	0.0000093193474256	0.0000054209058680	0.0000038873451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5440000000000000	0.0000093143474256	0.0000054189058597	0.0000038783451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5449999999999999	0.0000093093474256	0.0000054169058728	0.0000038693451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5459999999999998	0.0000093043474256	0.0000054149058717	0.0000038603451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5469999999999997	0.0000092993474256	0.0000054129058776	0.0000038513451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5480000000000000	0.0000092943474256	0.0000054109058552	0.0000038423451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5489999999999999	0.0000092893474256	0.0000054089058896	0.0000038333451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5499999999999998	0.0000092843474256	0.0000054069058671	0.0000038243451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5509999999999997	0.0000092793474256	0.0000054049058873	0.0000038153451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5520000000000000	0.0000092743474256	0.0000054029058577	0.0000038063451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5529999999999999	0.0000092693474256	0.0000054009058779	0.0000037973451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5539999999999998	0.0000092643474256	0.0000053989058768	0.0000037883451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5549999999999997	0.0000092593474256	0.0000053969058827	0.0000037793451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5560000000000000	0.0000092543474256	0.0000053949058532	0.0000037703451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5569999999999999	0.0000092493474256	0.0000053929058805	0.0000037613451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5579999999999998	0.0000092443474256	0.0000053909058793	0.0000037523451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5589999999999997	0.0000092393474256	0.0000053889058782	0.0000037433451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5600000000000001	0.0000092343474256	0.0000053869058557	0.0000037343451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5609999999999999	0.0000092293474256	0.0000053849058688	0.0000037253451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5619999999999998	0.0000092243474256	0.0000053829058819	0.0000037163451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5629999999999997	0.0000092193474256	0.0000053809058736	0.0000037073451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5640000000000001	0.0000092143474256	0.0000053789058583	0.0000036983451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5649999999999999	0.0000092093474256	0.0000053769058714	0.0000036893451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5659999999999998	0.0000092043474256	0.0000053749058773	0.0000036803451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5669999999999997	0.0000091993474256	0.0000053729058762	0.0000036713451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5680000000000001	0.0000091943474256	0.0000053709058537	0.0000036623451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5690000000000000	0.0000091893474256	0.0000053689058739	0.0000036533451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5699999999999998	0.0000091843474256	0.0000053669058728	0.0000036443451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5709999999999997	0.0000091793474256	0.0000053649058716	0.0000036353451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5720000000000001	0.0000091743474256	0.0000053629058634	0.0000036263451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5730000000000000	0.0000091693474256	0.0000053609058836	0.0000036173451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5739999999999998	0.0000091643474256	0.0000053589058753	0.0000036083451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5749999999999997	0.0000091593474256	0.0000053569058742	0.0000035993451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5759999999999996	0.0000091543474256	0.0000053549058802	0.0000035903451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5770000000000000	0.0000091493474256	0.0000053529058648	0.0000035813451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5779999999999998	0.0000091443474256	0.0000053509058779	0.0000035723451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5789999999999997	0.0000091393474256	0.0000053489058767	0.0000035633451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5799999999999996	0.0000091343474256	0.0000053469058685	0.0000035543451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5810000000000000	0.0000091293474256	0.0000053449058674	0.0000035453451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5819999999999999	0.0000091243474256	0.0000053429058804	0.0000035363451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5829999999999997	0.0000091193474256	0.0000053409058651	0.0000035273451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5839999999999996	0.0000091143474256	0.0000053389058782	0.0000035183451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5850000000000000	0.0000091093474256	0.0000053369058699	0.0000035093451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5859999999999999	0.0000091043474256	0.0000053349058688	0.0000035003451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5869999999999997	0.0000090993474256	0.0000053329058747	0.0000034913451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5879999999999996	0.0000090943474256	0.0000053309058736	0.0000034823451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5890000000000000	0.0000090893474256	0.0000053289058654	0.0000034733451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5899999999999999	0.0000090843474256	0.0000053269058642	0.0000034643451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5909999999999997	0.0000090793474256	0.0000053249058702	0.0000034553451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5919999999999996	0.0000090743474256	0.0000053229058833	0.0000034463451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5930000000000000	0.0000090693474256	0.0000053209058537	0.0000034373451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5939999999999999	0.0000090643474256	0.0000053189058739	0.0000034283451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5949999999999998	0.0000090593474256	0.0000053169058656	0.0000034193451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5959999999999996	0.0000090543474256	0.0000053149058858	0.0000034103451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5970000000000000	0.0000090493474256	0.0000053129058563	0.0000034013451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5979999999999999	0.0000090443474256	0.0000053109058835	0.0000033923451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5989999999999998	0.0000090393474256	0.0000053089058753	0.0000033833451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.5999999999999996	0.0000090343474256	0.0000053069058813	0.0000033743451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6010000000000000	0.0000090293474256	0.0000053049058659	0.0000033653451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6019999999999999	0.0000090243474256	0.0000053029058648	0.0000033563451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6029999999999998	0.0000090193474256	0.0000053009058779	0.0000033473451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6039999999999996	0.0000090143474256	0.0000052989058767	0.0000033383451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6050000000000000	0.0000090093474256	0.0000052969058685	0.0000033293451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6059999999999999	0.0000090043474256	0.0000052949058744	0.0000033203451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6069999999999998	0.0000089993474256	0.0000052929058804	0.0000033113451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6079999999999997	0.0000089943474256	0.0000052909058651	0.0000033023451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6090000000000000	0.0000089893474256	0.0000052889058639	0.0000032933451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6099999999999999	0.0000089843474256	0.0000052869058699	0.0000032843451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6109999999999998	0.0000089793474256	0.0000052849058830	0.0000032753451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6119999999999997	0.0000089743474256	0.0000052829058747	0.0000032663451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6130000000000000	0.0000089693474256	0.0000052809058594	0.0000032573451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6139999999999999	0.0000089643474256	0.0000052789058582	0.0000032483451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6149999999999998	0.0000089593474256	0.0000052769058784	0.0000032393451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6159999999999997	0.0000089543474256	0.0000052749058702	0.0000032303451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6170000000000000	0.0000089493474256	0.0000052729058477	0.0000032213451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6179999999999999	0.0000089443474256	0.0000052709058679	0.0000032123451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6189999999999998	0.0000089393474256	0.0000052689058739	0.0000032033451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6199999999999997	0.0000089343474256	0.0000052669058656	0.0000031943451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6210000000000000	0.0000089293474256	0.0000052649058574	0.0000031853451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6219999999999999	0.0000089243474256	0.0000052629058633	0.0000031763451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6229999999999998	0.0000089193474256	0.0000052609058693	0.0000031673451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6239999999999997	0.0000089143474256	0.0000052589058611	0.0000031583451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6250000000000000	0.0000089093474256	0.0000052569058528	0.0000031493451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6259999999999999	0.0000089043474256	0.0000052549058730	0.0000031403451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6269999999999998	0.0000088993474256	0.0000052529058648	0.0000031313451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6279999999999997	0.0000088943474256	0.0000052509058565	0.0000031223451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6290000000000000	0.0000088893474256	0.0000052489058625	0.0000031133451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6299999999999999	0.0000088843474256	0.0000052469058542	0.0000031043451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6309999999999998	0.0000088793474256	0.0000052449058744	0.0000030953451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6319999999999997	0.0000088743474256	0.0000052429058662	0.0000030863451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6330000000000000	0.0000088693474256	0.0000052409058579	0.0000030773451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6339999999999999	0.0000088643474256	0.0000052389058781	0.0000030683451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6349999999999998	0.0000088593474256	0.0000052369058699	0.0000030593451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6359999999999997	0.0000088543474256	0.0000052349058758	0.0000030503451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6370000000000000	0.0000088493474256	0.0000052329058392	0.0000030413451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6379999999999999	0.0000088443474256	0.0000052309058878	0.0000030323451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6389999999999998	0.0000088393474256	0.0000052289058511	0.0000030233451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6399999999999997	0.0000088343474256	0.0000052269058855	0.0000030143451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6410000000000000	0.0000088293474256	0.0000052249058488	0.0000030053451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6419999999999999	0.0000088243474256	0.0000052229058690	0.0000029963451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6429999999999998	0.0000088193474256	0.0000052209058608	0.0000029873451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6439999999999997	0.0000088143474256	0.0000052189058667	0.0000029783451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6450000000000000	0.0000088093474256	0.0000052169058585	0.0000029693451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6459999999999999	0.0000088043474256	0.0000052149058645	0.0000029603451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6469999999999998	0.0000087993474256	0.0000052129058704	0.0000029513451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6479999999999997	0.0000087943474256	0.0000052109058764	0.0000029423451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6490000000000000	0.0000087893474256	0.0000052089058397	0.0000029333451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6499999999999999	0.0000087843474256	0.0000052069058599	0.0000029243451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6509999999999998	0.0000087793474256	0.0000052049058801	0.0000029153451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6519999999999997	0.0000087743474256	0.0000052029058576	0.0000029063451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6530000000000000	0.0000087693474256	0.0000052009058494	0.0000028973451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6539999999999999	0.0000087643474256	0.0000051989058696	0.0000028883451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6549999999999998	0.0000087593474256	0.0000051969058755	0.0000028793451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6559999999999997	0.0000087543474256	0.0000051949058673	0.0000028703451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6570000000000000	0.0000087493474256	0.0000051929058591	0.0000028613451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6579999999999999	0.0000087443474256	0.0000051909058650	0.0000028523451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6589999999999998	0.0000087393474256	0.0000051889058710	0.0000028433451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6599999999999997	0.0000087343474256	0.0000051869058627	0.0000028343451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6610000000000000	0.0000087293474256	0.0000051849058687	0.0000028253451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6619999999999999	0.0000087243474256	0.0000051829058747	0.0000028163451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6629999999999998	0.0000087193474256	0.0000051809058664	0.0000028073451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6639999999999997	0.0000087143474256	0.0000051789058582	0.0000027983451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6650000000000000	0.0000087093474256	0.0000051769058642	0.0000027893451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6659999999999999	0.0000087043474256	0.0000051749058559	0.0000027803451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6669999999999998	0.0000086993474256	0.0000051729058761	0.0000027713451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6679999999999997	0.0000086943474256	0.0000051709058679	0.0000027623451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6690000000000000	0.0000086893474256	0.0000051689058596	0.0000027533451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6699999999999999	0.0000086843474256	0.0000051669058514	0.0000027443451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6709999999999998	0.0000086793474256	0.0000051649058858	0.0000027353451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6719999999999997	0.0000086743474256	0.0000051629058491	0.0000027263451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6730000000000000	0.0000086693474256	0.0000051609058693	0.0000027173451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6739999999999999	0.0000086643474256	0.0000051589058610	0.0000027083451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6749999999999998	0.0000086593474256	0.0000051569058670	0.0000026993451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6759999999999997	0.0000086543474256	0.0000051549058588	0.0000026903451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6770000000000000	0.0000086493474256	0.0000051529058505	0.0000026813451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6779999999999999	0.0000086443474256	0.0000051509058707	0.0000026723451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6789999999999998	0.0000086393474256	0.0000051489058624	0.0000026633451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6799999999999997	0.0000086343474256	0.0000051469058826	0.0000026543451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6810000000000000	0.0000086293474256	0.0000051449058460	0.0000026453451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6819999999999999	0.0000086243474256	0.0000051429058661	0.0000026363451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6829999999999998	0.0000086193474256	0.0000051409058721	0.0000026273451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6839999999999997	0.0000086143474256	0.0000051389058639	0.0000026183451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6850000000000001	0.0000086093474256	0.0000051369058556	0.0000026093451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6859999999999999	0.0000086043474256	0.0000051349058758	0.0000026003451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6869999999999998	0.0000085993474256	0.0000051329058676	0.0000025913451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6879999999999997	0.0000085943474256	0.0000051309058735	0.0000025823451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6890000000000001	0.0000085893474256	0.0000051289058511	0.0000025733451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6899999999999999	0.0000085843474256	0.0000051269058712	0.0000025643451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6909999999999998	0.0000085793474256	0.0000051249058630	0.0000025553451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6919999999999997	0.0000085743474256	0.0000051229058690	0.0000025463451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6930000000000001	0.0000085693474256	0.0000051209058465	0.0000025373451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6940000000000000	0.0000085643474256	0.0000051189058809	0.0000025283451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6949999999999998	0.0000085593474256	0.0000051169058585	0.0000025193451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6959999999999997	0.0000085543474256	0.0000051149058644	0.0000025103451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6970000000000001	0.0000085493474256	0.0000051129058562	0.0000025013451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6980000000000000	0.0000085443474256	0.0000051109058764	0.0000024923451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6989999999999998	0.0000085393474256	0.0000051089058539	0.0000024833451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.6999999999999997	0.0000085343474256	0.0000051069058741	0.0000024743451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7009999999999996	0.0000085293474256	0.0000051049058516	0.0000024653451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7020000000000000	0.0000085243474256	0.0000051029058576	0.0000024563451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7029999999999998	0.0000085193474256	0.0000051009058636	0.0000024473451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7039999999999997	0.0000085143474256	0.0000050989058695	0.0000024383451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7049999999999996	0.0000085093474256	0.0000050969058755	0.0000024293451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7060000000000000	0.0000085043474256	0.0000050949058530	0.0000024203451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7069999999999999	0.0000084993474256	0.0000050929058874	0.0000024113451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7079999999999997	0.0000084943474256	0.0000050909058650	0.0000024023451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7089999999999996	0.0000084893474256	0.0000050889058709	0.0000023933451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7100000000000000	0.0000084843474256	0.0000050869058485	0.0000023843451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7109999999999999	0.0000084793474256	0.0000050849058829	0.0000023753451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7119999999999997	0.0000084743474256	0.0000050829058604	0.0000023663451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7129999999999996	0.0000084693474256	0.0000050809058664	0.0000023573451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7140000000000000	0.0000084643474256	0.0000050789058439	0.0000023483451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7149999999999999	0.0000084593474256	0.0000050769058783	0.0000023393451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7159999999999997	0.0000084543474256	0.0000050749058701	0.0000023303451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7169999999999996	0.0000084493474256	0.0000050729058618	0.0000023213451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7180000000000000	0.0000084443474256	0.0000050709058536	0.0000023123451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7189999999999999	0.0000084393474256	0.0000050689058738	0.0000023033451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7199999999999998	0.0000084343474256	0.0000050669058513	0.0000022943451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7209999999999996	0.0000084293474256	0.0000050649058857	0.0000022853451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7220000000000000	0.0000084243474256	0.0000050629058348	0.0000022763451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7229999999999999	0.0000084193474256	0.0000050609058692	0.0000022673451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7239999999999998	0.0000084143474256	0.0000050589058610	0.0000022583451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7249999999999996	0.0000084093474256	0.0000050569058670	0.0000022493451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7260000000000000	0.0000084043474256	0.0000050549058587	0.0000022403451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7269999999999999	0.0000083993474256	0.0000050529058647	0.0000022313451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7279999999999998	0.0000083943474256	0.0000050509058706	0.0000022223451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7289999999999996	0.0000083893474256	0.0000050489058624	0.0000022133451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7300000000000000	0.0000083843474256	0.0000050469058542	0.0000022043451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7309999999999999	0.0000083793474256	0.0000050449058743	0.0000021953451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7319999999999998	0.0000083743474256	0.0000050429058803	0.0000021863451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7329999999999997	0.0000083693474256	0.0000050409058579	0.0000021773451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7340000000000000	0.0000083643474256	0.0000050389058638	0.0000021683451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7349999999999999	0.0000083593474256	0.0000050369058556	0.0000021593451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7359999999999998	0.0000083543474256	0.0000050349058758	0.0000021503451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7369999999999997	0.0000083493474256	0.0000050329058675	0.0000021413451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7380000000000000	0.0000083443474256	0.0000050309058451	0.0000021323451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7389999999999999	0.0000083393474256	0.0000050289058794	0.0000021233451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7399999999999998	0.0000083343474256	0.0000050269058712	0.0000021143451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7409999999999997	0.0000083293474256	0.0000050249058630	0.0000021053451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7420000000000000	0.0000083243474256	0.0000050229058547	0.0000020963451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7429999999999999	0.0000083193474256	0.0000050209058607	0.0000020873451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7439999999999998	0.0000083143474256	0.0000050189058667	0.0000020783451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7449999999999997	0.0000083093474256	0.0000050169058584	0.0000020693451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7460000000000000	0.0000083043474256	0.0000050149058644	0.0000020603451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7469999999999999	0.0000082993474256	0.0000050129058561	0.0000020513451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7479999999999998	0.0000082943474256	0.0000050109058763	0.0000020423451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7489999999999997	0.0000082893474256	0.0000050089058539	0.0000020333451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7500000000000000	0.0000082843474256	0.0000050069058598	0.0000020243451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7509999999999999	0.0000082793474256	0.0000050049058658	0.0000020153451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7519999999999998	0.0000082743474256	0.0000050029058718	0.0000020063451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7529999999999997	0.0000082693474256	0.0000050009058777	0.0000019973451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7540000000000000	0.0000082643474256	0.0000049989058553	0.0000019883451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7549999999999999	0.0000082593474256	0.0000049969058755	0.0000019793451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7559999999999998	0.0000082543474256	0.0000049949058672	0.0000019703451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7569999999999997	0.0000082493474256	0.0000049929058590	0.0000019613451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7580000000000000	0.0000082443474256	0.0000049909058507	0.0000019523451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7589999999999999	0.0000082393474256	0.0000049889058851	0.0000019433451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7599999999999998	0.0000082343474256	0.0000049869058484	0.0000019343451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7609999999999997	0.0000082293474256	0.0000049849058828	0.0000019253451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7620000000000000	0.0000082243474256	0.0000049829058462	0.0000019163451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7629999999999999	0.0000082193474256	0.0000049809058664	0.0000019073451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7639999999999998	0.0000082143474256	0.0000049789058723	0.0000018983451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7649999999999997	0.0000082093474256	0.0000049769058641	0.0000018893451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7660000000000000	0.0000082043474256	0.0000049749058558	0.0000018803451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7669999999999999	0.0000081993474256	0.0000049729058618	0.0000018713451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7679999999999998	0.0000081943474256	0.0000049709058678	0.0000018623451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7689999999999997	0.0000081893474256	0.0000049689058737	0.0000018533451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7700000000000000	0.0000081843474256	0.0000049669058513	0.0000018443451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7709999999999999	0.0000081793474256	0.0000049649058573	0.0000018353451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7719999999999998	0.0000081743474256	0.0000049629058632	0.0000018263451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7729999999999997	0.0000081693474256	0.0000049609058692	0.0000018173451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7740000000000000	0.0000081643474256	0.0000049589058609	0.0000018083451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7749999999999999	0.0000081593474256	0.0000049569058669	0.0000017993451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7759999999999998	0.0000081543474256	0.0000049549058729	0.0000017903451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7769999999999997	0.0000081493474256	0.0000049529058646	0.0000017813451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7780000000000000	0.0000081443474256	0.0000049509058564	0.0000017723451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7789999999999999	0.0000081393474256	0.0000049489058766	0.0000017633451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7799999999999998	0.0000081343474256	0.0000049469058683	0.0000017543451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7809999999999997	0.0000081293474256	0.0000049449058601	0.0000017453451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7820000000000000	0.0000081243474256	0.0000049429058661	0.0000017363451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7829999999999999	0.0000081193474256	0.0000049409058720	0.0000017273451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7839999999999998	0.0000081143474256	0.0000049389058638	0.0000017183451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7849999999999997	0.0000081093474256	0.0000049369058697	0.0000017093451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7860000000000000	0.0000081043474256	0.0000049349058473	0.0000017003451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7869999999999999	0.0000080993474256	0.0000049329058675	0.0000016913451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7879999999999998	0.0000080943474256	0.0000049309058734	0.0000016823451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7889999999999997	0.0000080893474256	0.0000049289058652	0.0000016733451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7900000000000000	0.0000080843474256	0.0000049269058427	0.0000016643451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7909999999999999	0.0000080793474256	0.0000049249058771	0.0000016553451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7919999999999998	0.0000080743474256	0.0000049229058547	0.0000016463451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7929999999999997	0.0000080693474256	0.0000049209058749	0.0000016373451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7940000000000000	0.0000080643474256	0.0000049189058524	0.0000016283451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7949999999999999	0.0000080593474256	0.0000049169058584	0.0000016193451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7959999999999998	0.0000080543474256	0.0000049149058785	0.0000016103451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7969999999999997	0.0000080493474256	0.0000049129058561	0.0000016013451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7980000000000000	0.0000080443474256	0.0000049109058478	0.0000015923451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7989999999999999	0.0000080393474256	0.0000049089058822	0.0000015833451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.7999999999999998	0.0000080343474256	0.0000049069058598	0.0000015743451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8009999999999997	0.0000080293474256	0.0000049049058800	0.0000015653451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8020000000000000	0.0000080243474256	0.0000049029058433	0.0000015563451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8029999999999999	0.0000080193474256	0.0000049009058777	0.0000015473451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8039999999999998	0.0000080143474256	0.0000048989058694	0.0000015383451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8049999999999997	0.0000080093474256	0.0000048969058754	0.0000015293451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8060000000000000	0.0000080043474256	0.0000048949058530	0.0000015203451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8069999999999999	0.0000079993474256	0.0000048929058731	0.0000015113451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8079999999999998	0.0000079943474256	0.0000048909058507	0.0000015023451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8089999999999997	0.0000079893474256	0.0000048889058709	0.0000014933451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8100000000000001	0.0000079843474256	0.0000048869058626	0.0000014843451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8109999999999999	0.0000079793474256	0.0000048849058544	0.0000014753451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8119999999999998	0.0000079743474256	0.0000048829058746	0.0000014663451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8129999999999997	0.0000079693474256	0.0000048809058663	0.0000014573451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8140000000000001	0.0000079643474256	0.0000048789058439	0.0000014483451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8149999999999999	0.0000079593474256	0.0000048769058782	0.0000014393451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8159999999999998	0.0000079543474256	0.0000048749058558	0.0000014303451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8169999999999997	0.0000079493474256	0.0000048729058760	0.0000014213451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8180000000000001	0.0000079443474256	0.0000048709058393	0.0000014123451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8190000000000000	0.0000079393474256	0.0000048689058737	0.0000014033451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8199999999999998	0.0000079343474256	0.0000048669058512	0.0000013943451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8209999999999997	0.0000079293474256	0.0000048649058856	0.0000013853451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8220000000000001	0.0000079243474256	0.0000048629058490	0.0000013763451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8230000000000000	0.0000079193474256	0.0000048609058691	0.0000013673451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8239999999999998	0.0000079143474256	0.0000048589058751	0.0000013583451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8249999999999997	0.0000079093474256	0.0000048569058669	0.0000013493451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8260000000000001	0.0000079043474256	0.0000048549058586	0.0000013403451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8270000000000000	0.0000078993474256	0.0000048529058646	0.0000013313451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8279999999999998	0.0000078943474256	0.0000048509058706	0.0000013223451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8289999999999997	0.0000078893474256	0.0000048489058623	0.0000013133451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8299999999999996	0.0000078843474256	0.0000048469058825	0.0000013043451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8310000000000000	0.0000078793474256	0.0000048449058458	0.0000012953451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8319999999999999	0.0000078743474256	0.0000048429058802	0.0000012863451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8329999999999997	0.0000078693474256	0.0000048409058578	0.0000012773451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8339999999999996	0.0000078643474256	0.0000048389058637	0.0000012683451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8350000000000000	0.0000078593474256	0.0000048369058555	0.0000012593451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8359999999999999	0.0000078543474256	0.0000048349058757	0.0000012503451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8369999999999997	0.0000078493474256	0.0000048329058532	0.0000012413451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8379999999999996	0.0000078443474256	0.0000048309058734	0.0000012323451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8390000000000000	0.0000078393474256	0.0000048289058509	0.0000012233451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8399999999999999	0.0000078343474256	0.0000048269058711	0.0000012143451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8409999999999997	0.0000078293474256	0.0000048249058629	0.0000012053451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8419999999999996	0.0000078243474256	0.0000048229058688	0.0000011963451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8430000000000000	0.0000078193474256	0.0000048209058464	0.0000011873451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8439999999999999	0.0000078143474256	0.0000048189058666	0.0000011783451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8449999999999998	0.0000078093474256	0.0000048169058583	0.0000011693451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8459999999999996	0.0000078043474256	0.0000048149058643	0.0000011603451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8470000000000000	0.0000077993474256	0.0000048129058703	0.0000011513451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8479999999999999	0.0000077943474256	0.0000048109058620	0.0000011423451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8489999999999998	0.0000077893474256	0.0000048089058822	0.0000011333451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8499999999999996	0.0000077843474256	0.0000048069058597	0.0000011243451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8510000000000000	0.0000077793474256	0.0000048049058515	0.0000011153451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8519999999999999	0.0000077743474256	0.0000048029058717	0.0000011063451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8529999999999998	0.0000077693474256	0.0000048009058776	0.0000010973451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8539999999999996	0.0000077643474256	0.0000047989058552	0.0000010883451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8550000000000000	0.0000077593474256	0.0000047969058612	0.0000010793451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8559999999999999	0.0000077543474256	0.0000047949058671	0.0000010703451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8569999999999998	0.0000077493474256	0.0000047929058731	0.0000010613451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8579999999999997	0.0000077443474256	0.0000047909058648	0.0000010523451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8590000000000000	0.0000077393474256	0.0000047889058566	0.0000010433451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8599999999999999	0.0000077343474256	0.0000047869058484	0.0000010343451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8609999999999998	0.0000077293474256	0.0000047849058828	0.0000010253451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8619999999999997	0.0000077243474256	0.0000047829058603	0.0000010163451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8630000000000000	0.0000077193474256	0.0000047809058521	0.0000010073451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8639999999999999	0.0000077143474256	0.0000047789058580	0.0000009983451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8649999999999998	0.0000077093474256	0.0000047769058782	0.0000009893451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8659999999999997	0.0000077043474256	0.0000047749058557	0.0000009803451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8670000000000000	0.0000076993474256	0.0000047729058475	0.0000009713451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8679999999999999	0.0000076943474256	0.0000047709058677	0.0000009623451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8689999999999998	0.0000076893474256	0.0000047689058737	0.0000009533451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8699999999999997	0.0000076843474256	0.0000047669058654	0.0000009443451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8710000000000000	0.0000076793474256	0.0000047649058572	0.0000009353451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8719999999999999	0.0000076743474256	0.0000047629058773	0.0000009263451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8729999999999998	0.0000076693474256	0.0000047609058691	0.0000009173451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8739999999999997	0.0000076643474256	0.0000047589058609	0.0000009083451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8750000000000000	0.0000076593474256	0.0000047569058526	0.0000008993451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8759999999999999	0.0000076543474256	0.0000047549058728	0.0000008903451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8769999999999998	0.0000076493474256	0.0000047529058645	0.0000008813451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8779999999999997	0.0000076443474256	0.0000047509058705	0.0000008723451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8790000000000000	0.0000076393474256	0.0000047489058623	0.0000008633451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8799999999999999	0.0000076343474256	0.0000047469058682	0.0000008543451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8809999999999998	0.0000076293474256	0.0000047449058600	0.0000008453451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8819999999999997	0.0000076243474256	0.0000047429058802	0.0000008363451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8830000000000000	0.0000076193474256	0.0000047409058435	0.0000008273451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8839999999999999	0.0000076143474256	0.0000047389058637	0.0000008183451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8849999999999998	0.0000076093474256	0.0000047369058697	0.0000008093451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8859999999999997	0.0000076043474256	0.0000047349058756	0.0000008003451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8870000000000000	0.0000075993474256	0.0000047329058390	0.0000007913451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8879999999999999	0.0000075943474256	0.0000047309058733	0.0000007823451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8889999999999998	0.0000075893474256	0.0000047289058509	0.0000007733451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8899999999999997	0.0000075843474256	0.0000047269058711	0.0000007643451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8910000000000000	0.0000075793474256	0.0000047249058486	0.0000007553451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8919999999999999	0.0000075743474256	0.0000047229058688	0.0000007463451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8929999999999998	0.0000075693474256	0.0000047209058748	0.0000007373451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8939999999999997	0.0000075643474256	0.0000047189058665	0.0000007283451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8950000000000000	0.0000075593474256	0.0000047169058583	0.0000007193451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8959999999999999	0.0000075543474256	0.0000047149058642	0.0000007103451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8969999999999998	0.0000075493474256	0.0000047129058702	0.0000007013451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8979999999999997	0.0000075443474256	0.0000047109058762	0.0000006923451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8990000000000000	0.0000075393474256	0.0000047089058537	0.0000006833451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.8999999999999999	0.0000075343474256	0.0000047069058739	0.0000006743451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9009999999999998	0.0000075293474256	0.0000047049058657	0.0000006653451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9019999999999997	0.0000075243474256	0.0000047029058716	0.0000006563451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9030000000000000	0.0000075193474256	0.0000047009058492	0.0000006473451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9039999999999999	0.0000075143474256	0.0000046989058694	0.0000006383451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9049999999999998	0.0000075093474256	0.0000046969058753	0.0000006293451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9059999999999997	0.0000075043474256	0.0000046949058529	0.0000006203451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9070000000000000	0.0000074993474256	0.0000046929058588	0.0000006113451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9079999999999999	0.0000074943474256	0.0000046909058648	0.0000006023451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9089999999999998	0.0000074893474256	0.0000046889058708	0.0000005933451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9099999999999997	0.0000074843474256	0.0000046869058625	0.0000005843451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9110000000000000	0.0000074793474256	0.0000046849058543	0.0000005753451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9119999999999999	0.0000074743474256	0.0000046829058603	0.0000005663451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9129999999999998	0.0000074693474256	0.0000046809058662	0.0000005573451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9139999999999997	0.0000074643474256	0.0000046789058722	0.0000005483451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9150000000000000	0.0000074593474256	0.0000046769058497	0.0000005393451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9159999999999999	0.0000074543474256	0.0000046749058557	0.0000005303451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9169999999999998	0.0000074493474256	0.0000046729058759	0.0000005213451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9179999999999997	0.0000074443474256	0.0000046709058676	0.0000005123451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9190000000000000	0.0000074393474256	0.0000046689058452	0.0000005033451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9199999999999999	0.0000074343474256	0.0000046669058796	0.0000004943451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9209999999999998	0.0000074293474256	0.0000046649058713	0.0000004853451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9219999999999997	0.0000074243474256	0.0000046629058773	0.0000004763451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9230000000000000	0.0000074193474256	0.0000046609058406	0.0000004673451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9239999999999999	0.0000074143474256	0.0000046589058750	0.0000004583451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9249999999999998	0.0000074093474256	0.0000046569058668	0.0000004493451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9259999999999997	0.0000074043474256	0.0000046549058727	0.0000004403451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9270000000000000	0.0000073993474256	0.0000046529058503	0.0000004313451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9279999999999999	0.0000073943474256	0.0000046509058705	0.0000004223451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9289999999999998	0.0000073893474256	0.0000046489058622	0.0000004133451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9299999999999997	0.0000073843474256	0.0000046469058682	0.0000004043451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9310000000000000	0.0000073793474256	0.0000046449058457	0.0000003953451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9319999999999999	0.0000073743474256	0.0000046429058801	0.0000003863451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9329999999999998	0.0000073693474256	0.0000046409058577	0.0000003773451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9339999999999997	0.0000073643474256	0.0000046389058779	0.0000003683451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9350000000000001	0.0000073593474256	0.0000046369058412	0.0000003593451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9359999999999999	0.0000073543474256	0.0000046349058614	0.0000003503451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9369999999999998	0.0000073493474256	0.0000046329058673	0.0000003413451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9379999999999997	0.0000073443474256	0.0000046309058591	0.0000003323451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9390000000000001	0.0000073393474256	0.0000046289058509	0.0000003233451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9399999999999999	0.0000073343474256	0.0000046269058710	0.0000003143451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9409999999999998	0.0000073293474256	0.0000046249058770	0.0000003053451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9419999999999997	0.0000073243474256	0.0000046229058688	0.0000002963451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9430000000000001	0.0000073193474256	0.0000046209058463	0.0000002873451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9440000000000000	0.0000073143474256	0.0000046189058807	0.0000002783451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9449999999999998	0.0000073093474256	0.0000046169058724	0.0000002693451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9459999999999997	0.0000073043474256	0.0000046149058500	0.0000002603451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9470000000000001	0.0000072993474256	0.0000046129058702	0.0000002513451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9480000000000000	0.0000072943474256	0.0000046109058619	0.0000002423451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9489999999999998	0.0000072893474256	0.0000046089058679	0.0000002333451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9499999999999997	0.0000072843474256	0.0000046069058739	0.0000002243451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9510000000000001	0.0000072793474256	0.0000046049058514	0.0000002153451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9520000000000000	0.0000072743474256	0.0000046029058574	0.0000002063451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9529999999999998	0.0000072693474256	0.0000046009058776	0.0000001973451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9539999999999997	0.0000072643474256	0.0000045989058551	0.0000001883451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9550000000000001	0.0000072593474256	0.0000045969058611	0.0000001793451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9560000000000000	0.0000072543474256	0.0000045949058670	0.0000001703451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9569999999999999	0.0000072493474256	0.0000045929058730	0.0000001613451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9579999999999997	0.0000072443474256	0.0000045909058648	0.0000001523451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9589999999999996	0.0000072393474256	0.0000045889058707	0.0000001433451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9600000000000000	0.0000072343474256	0.0000045869058341	0.0000001343451502	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9609999999999999	0.0000072293474256	0.0000045849058685	0.0000001253451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9619999999999997	0.0000072243474256	0.0000045829058744	0.0000001163451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9629999999999996	0.0000072193474256	0.0000045809058662	0.0000001073451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9640000000000000	0.0000072143474256	0.0000045789058437	0.0000000983451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9649999999999999	0.0000072093474256	0.0000045769058639	0.0000000893451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9659999999999997	0.0000072043474256	0.0000045749058699	0.0000000803451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9669999999999996	0.0000071993474256	0.0000045729058758	0.0000000713451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9680000000000000	0.0000071943474256	0.0000045709058534	0.0000000623451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9689999999999999	0.0000071893474256	0.0000045689058594	0.0000000533451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9699999999999998	0.0000071843474256	0.0000045669058795	0.0000000443451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9709999999999996	0.0000071793474256	0.0000045649058713	0.0000000353451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9720000000000000	0.0000071743474256	0.0000045629058488	0.0000000263451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9729999999999999	0.0000071693474256	0.0000045609058690	0.0000000173451503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9739999999999998	0.0000071643474256	0.0000045589058750	0.0000000083451504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9749999999999996	0.0000071593474256	0.0000045569058667	-0.0000000006548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9760000000000000	0.0000071543474256	0.0000045549058443	-0.0000000096548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9769999999999999	0.0000071493474256	0.0000045529058645	-0.0000000186548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9779999999999998	0.0000071443474256	0.0000045509058704	-0.0000000276548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9789999999999996	0.0000071393474256	0.0000045489058622	-0.0000000366548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9800000000000000	0.0000071343474256	0.0000045469058539	-0.0000000456548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9809999999999999	0.0000071293474256	0.0000045449058741	-0.0000000546548496	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9819999999999998	0.0000071243474256	0.0000045429058659	-0.0000000636548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9829999999999997	0.0000071193474256	0.0000045409058576	-0.0000000726548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9840000000000000	0.0000071143474256	0.0000045389058494	-0.0000000816548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9849999999999999	0.0000071093474256	0.0000045369058696	-0.0000000906548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9859999999999998	0.0000071043474256	0.0000045349058613	-0.0000000996548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9869999999999997	0.0000070993474256	0.0000045329058673	-0.0000001086548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9880000000000000	0.0000070943474256	0.0000045309058448	-0.0000001176548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9889999999999999	0.0000070893474256	0.0000045289058792	-0.0000001266548496	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9899999999999998	0.0000070843474256	0.0000045269058710	-0.0000001356548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9909999999999997	0.0000070793474256	0.0000045249058770	-0.0000001446548496	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9920000000000000	0.0000070743474256	0.0000045229058403	-0.0000001536548498	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9929999999999999	0.0000070693474256	0.0000045209058747	-0.0000001626548496	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9939999999999998	0.0000070643474256	0.0000045189058664	-0.0000001716548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9949999999999997	0.0000070593474256	0.0000045169058724	-0.0000001806548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9960000000000000	0.0000070543474256	0.0000045149058500	-0.0000001896548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9969999999999999	0.0000070493474256	0.0000045129058701	-0.0000001986548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9979999999999998	0.0000070443474256	0.0000045109058619	-0.0000002076548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+3.9989999999999997	0.0000070393474256	0.0000045089058821	-0.0000002166548496	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.0000000000000000	0.0000070343474256	0.0000045069058454	-0.0000002256548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.0009999999999994	0.0000070293474256	0.0000045049058798	-0.0000002346548496	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.0019999999999998	0.0000070243474256	0.0000045029058573	-0.0000002436548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.0030000000000001	0.0000070193474256	0.0000045009058633	-0.0000002526548497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.0039999999999996	0.0000070143474256	0.0000044989058693	-0.0000002616548497	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0049999999999999	0.0000070093474256	0.0000044977197959	-0.0000002565229716	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.0060000000000002	0.0000070043474256	0.0000044965176319	-0.0000002513948449	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0069999999999997	0.0000069993474256	0.0000044952994254	-0.0000002462705194	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.0080000000000000	0.0000069943474256	0.0000044940650257	-0.0000002411500477	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.0090000000000003	0.0000069893474256	0.0000044928145662	-0.0000002360334789	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0099999999999998	0.0000069843474256	0.0000044915480946	-0.0000002309208627	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.0110000000000001	0.0000069793474256	0.0000044902655024	-0.0000002258122519	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0119999999999996	0.0000069743474256	0.0000044889669369	-0.0000002207076938	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.0129999999999999	0.0000069693474256	0.0000044876522467	-0.0000002156072434	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0139999999999993	0.0000069643474256	0.0000044863216496	-0.0000002105109447	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.0149999999999997	0.0000069593474256	0.0000044849749231	-0.0000002054188558	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0160000000000000	0.0000069543474256	0.0000044836122990	-0.0000002003310194	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0169999999999995	0.0000069493474256	0.0000044822337107	-0.0000001952474882	-0.0031415926535901	0.0000000000000000	0.0000000000000000	
+4.0179999999999998	0.0000069443474256	0.0000044808390773	-0.0000001901683168	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0190000000000001	0.0000069393474256	0.0000044794285168	-0.0000001850935508	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0199999999999996	0.0000069343474256	0.0000044780021041	-0.0000001800232369	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0209999999999999	0.0000069293474256	0.0000044765596588	-0.0000001749574352	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0220000000000002	0.0000069243474256	0.0000044751013550	-0.0000001698961874	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0229999999999997	0.0000069193474256	0.0000044736271964	-0.0000001648395435	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0240000000000000	0.0000069143474256	0.0000044721370874	-0.0000001597875603	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0250000000000004	0.0000069093474256	0.0000044706311308	-0.0000001547402824	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0259999999999998	0.0000069043474256	0.0000044691094150	-0.0000001496977540	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0270000000000001	0.0000068993474256	0.0000044675717308	-0.0000001446600411	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.0279999999999996	0.0000068943474256	0.0000044660183223	-0.0000001396271765	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0289999999999999	0.0000068893474256	0.0000044644490508	-0.0000001345992217	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0299999999999994	0.0000068843474256	0.0000044628640326	-0.0000001295762182	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0309999999999997	0.0000068793474256	0.0000044612631997	-0.0000001245582227	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0320000000000000	0.0000068743474256	0.0000044596466399	-0.0000001195452785	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.0329999999999995	0.0000068693474256	0.0000044580143840	-0.0000001145374334	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0339999999999998	0.0000068643474256	0.0000044563662930	-0.0000001095347515	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.0350000000000001	0.0000068593474256	0.0000044547025957	-0.0000001045372619	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0359999999999996	0.0000068543474256	0.0000044530231813	-0.0000000995450260	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0369999999999999	0.0000068493474256	0.0000044513280377	-0.0000000945580966	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.0380000000000003	0.0000068443474256	0.0000044496172801	-0.0000000895765124	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0389999999999997	0.0000068393474256	0.0000044478908962	-0.0000000846003256	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.0400000000000000	0.0000068343474256	0.0000044461488457	-0.0000000796295917	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0410000000000004	0.0000068293474256	0.0000044443912008	-0.0000000746643537	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0419999999999998	0.0000068243474256	0.0000044426180195	-0.0000000697046554	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0430000000000001	0.0000068193474256	0.0000044408292046	-0.0000000647505598	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0439999999999996	0.0000068143474256	0.0000044390248705	-0.0000000598021037	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.0449999999999999	0.0000068093474256	0.0000044372049478	-0.0000000548593473	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0459999999999994	0.0000068043474256	0.0000044353695646	-0.0000000499223249	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0469999999999997	0.0000067993474256	0.0000044335186233	-0.0000000449911008	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0480000000000000	0.0000067943474256	0.0000044316522518	-0.0000000400657084	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0489999999999995	0.0000067893474256	0.0000044297704086	-0.0000000351462048	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.0499999999999998	0.0000067843474256	0.0000044278730664	-0.0000000302326453	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.0510000000000002	0.0000067793474256	0.0000044259603525	-0.0000000253250624	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0519999999999996	0.0000067743474256	0.0000044240322251	-0.0000000204235135	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0529999999999999	0.0000067693474256	0.0000044220886988	-0.0000000155280476	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0540000000000003	0.0000067643474256	0.0000044201297740	-0.0000000106387163	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0549999999999997	0.0000067593474256	0.0000044181555492	-0.0000000057555550	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0560000000000000	0.0000067543474256	0.0000044161659544	-0.0000000008786264	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0570000000000004	0.0000067493474256	0.0000044141610598	0.0000000039920295	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0579999999999998	0.0000067443474256	0.0000044121409073	0.0000000088563688	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0590000000000002	0.0000067393474256	0.0000044101054268	0.0000000137143277	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0599999999999996	0.0000067343474256	0.0000044080547720	0.0000000185658818	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0609999999999999	0.0000067293474256	0.0000044059887748	0.0000000234109495	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0619999999999994	0.0000067243474256	0.0000044039076723	0.0000000282495223	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0629999999999997	0.0000067193474256	0.0000044018112963	0.0000000330815176	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0640000000000001	0.0000067143474256	0.0000043996997860	0.0000000379069099	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0649999999999995	0.0000067093474256	0.0000043975731544	0.0000000427256504	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0659999999999998	0.0000067043474256	0.0000043954313451	0.0000000475376761	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0670000000000002	0.0000066993474256	0.0000043932744685	0.0000000523429575	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0679999999999996	0.0000066943474256	0.0000043911024959	0.0000000571414370	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0690000000000000	0.0000066893474256	0.0000043889154540	0.0000000619330683	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.0700000000000003	0.0000066843474256	0.0000043867133416	0.0000000667177992	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0709999999999997	0.0000066793474256	0.0000043844962825	0.0000000714956043	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0720000000000001	0.0000066743474256	0.0000043822641365	0.0000000762664016	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0730000000000004	0.0000066693474256	0.0000043800170410	0.0000000810301688	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.0739999999999998	0.0000066643474256	0.0000043777550359	0.0000000857868632	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0750000000000002	0.0000066593474256	0.0000043754780781	0.0000000905364233	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0759999999999996	0.0000066543474256	0.0000043731862074	0.0000000952788060	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0770000000000000	0.0000066493474256	0.0000043708794358	0.0000001000139621	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0779999999999994	0.0000066443474256	0.0000043685577892	0.0000001047418453	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.0789999999999997	0.0000066393474256	0.0000043662213070	0.0000001094624129	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0800000000000001	0.0000066343474256	0.0000043638700286	0.0000001141756225	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.0809999999999995	0.0000066293474256	0.0000043615039656	0.0000001188814248	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.0819999999999999	0.0000066243474256	0.0000043591230883	0.0000001235797600	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.0830000000000002	0.0000066193474256	0.0000043567274632	0.0000001282705924	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0839999999999996	0.0000066143474256	0.0000043543171844	0.0000001329538940	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0850000000000000	0.0000066093474256	0.0000043518920979	0.0000001376295725	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0860000000000003	0.0000066043474256	0.0000043494523938	0.0000001422976250	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0869999999999997	0.0000065993474256	0.0000043469980830	0.0000001469580025	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.0880000000000001	0.0000065943474256	0.0000043445290394	0.0000001516106182	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0889999999999995	0.0000065893474256	0.0000043420454797	0.0000001562554786	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.0899999999999999	0.0000065843474256	0.0000043395472776	0.0000001608924964	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0909999999999993	0.0000065793474256	0.0000043370345670	0.0000001655216561	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0919999999999996	0.0000065743474256	0.0000043345072904	0.0000001701428890	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.0930000000000000	0.0000065693474256	0.0000043319655265	0.0000001747561646	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.0939999999999994	0.0000065643474256	0.0000043294092995	0.0000001793614374	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.0949999999999998	0.0000065593474256	0.0000043268385516	0.0000001839586375	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.0960000000000001	0.0000065543474256	0.0000043242534432	0.0000001885477593	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.0969999999999995	0.0000065493474256	0.0000043216539298	0.0000001931287370	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.0979999999999999	0.0000065443474256	0.0000043190399808	0.0000001977015081	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.0990000000000002	0.0000065393474256	0.0000043164117153	0.0000002022660558	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.0999999999999996	0.0000065343474256	0.0000043137691429	0.0000002068223305	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1010000000000000	0.0000065293474256	0.0000043111122466	0.0000002113702735	-0.0031415926535900	0.0000000000000000	-0.0000000000000000	
+4.1020000000000003	0.0000065243474256	0.0000043084410362	0.0000002159098345	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1029999999999998	0.0000065193474256	0.0000043057556974	0.0000002204410201	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1040000000000001	0.0000065143474256	0.0000043030559965	0.0000002249637014	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.1049999999999995	0.0000065093474256	0.0000043003421729	0.0000002294779027	-0.0031415926535901	0.0000000000000000	0.0000000000000000	
+4.1059999999999999	0.0000065043474256	0.0000042976141684	0.0000002339835520	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1069999999999993	0.0000064993474256	0.0000042948720465	0.0000002384806169	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.1079999999999997	0.0000064943474256	0.0000042921157359	0.0000002429690196	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1090000000000000	0.0000064893474256	0.0000042893454072	0.0000002474487646	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.1099999999999994	0.0000064843474256	0.0000042865610159	0.0000002519197834	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1109999999999998	0.0000064793474256	0.0000042837625443	0.0000002563820159	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1120000000000001	0.0000064743474256	0.0000042809501222	0.0000002608354540	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1129999999999995	0.0000064693474256	0.0000042781237184	0.0000002652800329	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1139999999999999	0.0000064643474256	0.0000042752833152	0.0000002697156923	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1150000000000002	0.0000064593474256	0.0000042724290551	0.0000002741424298	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1159999999999997	0.0000064543474256	0.0000042695608666	0.0000002785601656	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1170000000000000	0.0000064493474256	0.0000042666788121	0.0000002829688683	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.1180000000000003	0.0000064443474256	0.0000042637829135	0.0000002873684920	-0.0031415926535896	-0.0000000000000000	0.0000000000000000	
+4.1189999999999998	0.0000064393474256	0.0000042608732459	0.0000002917590109	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1200000000000001	0.0000064343474256	0.0000042579497647	0.0000002961403538	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1209999999999996	0.0000064293474256	0.0000042550125580	0.0000003005125003	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.1219999999999999	0.0000064243474256	0.0000042520615946	0.0000003048753837	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1229999999999993	0.0000064193474256	0.0000042490969886	0.0000003092289942	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1239999999999997	0.0000064143474256	0.0000042461186560	0.0000003135732443	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1250000000000000	0.0000064093474256	0.0000042431267237	0.0000003179081296	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1259999999999994	0.0000064043474256	0.0000042401212264	0.0000003222336098	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1269999999999998	0.0000063993474256	0.0000042371020931	0.0000003265496013	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1280000000000001	0.0000063943474256	0.0000042340694372	0.0000003308560954	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1289999999999996	0.0000063893474256	0.0000042310232799	0.0000003351530463	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1299999999999999	0.0000063843474256	0.0000042279636290	0.0000003394404024	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1310000000000002	0.0000063793474256	0.0000042248905057	0.0000003437181173	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.1319999999999997	0.0000063743474256	0.0000042218040487	0.0000003479861950	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1330000000000000	0.0000063693474256	0.0000042187040566	0.0000003522444943	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1340000000000003	0.0000063643474256	0.0000042155907853	0.0000003564930698	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1349999999999998	0.0000063593474256	0.0000042124641903	0.0000003607318473	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.1360000000000001	0.0000063543474256	0.0000042093242663	0.0000003649607691	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1369999999999996	0.0000063493474256	0.0000042061711118	0.0000003691798234	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1379999999999999	0.0000063443474256	0.0000042030046306	0.0000003733889115	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.1389999999999993	0.0000063393474256	0.0000041998250377	0.0000003775880744	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1399999999999997	0.0000063343474256	0.0000041966322111	0.0000003817772015	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1410000000000000	0.0000063293474256	0.0000041934262487	0.0000003859562815	-0.0031415926535901	0.0000000000000000	0.0000000000000000	
+4.1419999999999995	0.0000063243474256	0.0000041902072095	0.0000003901252859	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1429999999999998	0.0000063193474256	0.0000041869750364	0.0000003942841323	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.1440000000000001	0.0000063143474256	0.0000041837298398	0.0000003984328162	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1449999999999996	0.0000063093474256	0.0000041804716397	0.0000004025712912	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1459999999999999	0.0000063043474256	0.0000041772004434	0.0000004066995046	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.1470000000000002	0.0000062993474256	0.0000041739162580	0.0000004108174035	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.1479999999999997	0.0000062943474256	0.0000041706192315	0.0000004149250033	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1490000000000000	0.0000062893474256	0.0000041673092178	0.0000004190221761	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.1500000000000004	0.0000062843474256	0.0000041639863898	0.0000004231089502	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1509999999999998	0.0000062793474256	0.0000041606507926	0.0000004271852920	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.1520000000000001	0.0000062743474256	0.0000041573023442	0.0000004312511036	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.1529999999999996	0.0000062693474256	0.0000041539411787	0.0000004353063958	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.1539999999999999	0.0000062643474256	0.0000041505672397	0.0000004393510829	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.1549999999999994	0.0000062593474256	0.0000041471806858	0.0000004433851894	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.1559999999999997	0.0000062543474256	0.0000041437813851	0.0000004474085900	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1570000000000000	0.0000062493474256	0.0000041403694960	0.0000004514213097	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1579999999999995	0.0000062443474256	0.0000041369450753	0.0000004554233214	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1589999999999998	0.0000062393474256	0.0000041335080045	0.0000004594145051	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.1600000000000001	0.0000062343474256	0.0000041300584661	0.0000004633949001	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.1609999999999996	0.0000062293474256	0.0000041265964666	0.0000004673644529	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.1619999999999999	0.0000062243474256	0.0000041231219379	0.0000004713230689	-0.0031415926535896	-0.0000000000000000	0.0000000000000000	
+4.1630000000000003	0.0000062193474256	0.0000041196350367	0.0000004752707753	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1639999999999997	0.0000062143474256	0.0000041161357571	0.0000004792075114	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.1650000000000000	0.0000062093474256	0.0000041126241058	0.0000004831332230	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1660000000000004	0.0000062043474256	0.0000041091001517	0.0000004870478902	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.1669999999999998	0.0000061993474256	0.0000041055639386	0.0000004909514796	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1680000000000001	0.0000061943474256	0.0000041020153991	0.0000004948438947	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.1689999999999996	0.0000061893474256	0.0000040984547620	0.0000004987252074	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1699999999999999	0.0000061843474256	0.0000040948818490	0.0000005025952573	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1709999999999994	0.0000061793474256	0.0000040912968761	0.0000005064541103	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.1719999999999997	0.0000061743474256	0.0000040876997147	0.0000005103016329	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.1730000000000000	0.0000061693474256	0.0000040840905432	0.0000005141378709	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1739999999999995	0.0000061643474256	0.0000040804693314	0.0000005179627476	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1749999999999998	0.0000061593474256	0.0000040768360981	0.0000005217762153	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.1760000000000002	0.0000061543474256	0.0000040731909232	0.0000005255782626	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1769999999999996	0.0000061493474256	0.0000040695338253	0.0000005293688416	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.1779999999999999	0.0000061443474256	0.0000040658648110	0.0000005331478969	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1790000000000003	0.0000061393474256	0.0000040621839599	0.0000005369154176	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1799999999999997	0.0000061343474256	0.0000040584913024	0.0000005406713633	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1810000000000000	0.0000061293474256	0.0000040547868213	0.0000005444156631	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1820000000000004	0.0000061243474256	0.0000040510706315	0.0000005481483292	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1829999999999998	0.0000061193474256	0.0000040473427636	0.0000005518693212	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1840000000000002	0.0000061143474256	0.0000040436031521	0.0000005555785375	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1849999999999996	0.0000061093474256	0.0000040398519597	0.0000005592760213	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1859999999999999	0.0000061043474256	0.0000040360891210	0.0000005629616707	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.1869999999999994	0.0000060993474256	0.0000040323147978	0.0000005666355299	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.1879999999999997	0.0000060943474256	0.0000040285288776	0.0000005702974653	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1890000000000001	0.0000060893474256	0.0000040247315098	0.0000005739475137	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1899999999999995	0.0000060843474256	0.0000040209226771	0.0000005775856034	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1909999999999998	0.0000060793474256	0.0000040171024574	0.0000005812117251	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1920000000000002	0.0000060743474256	0.0000040132708100	0.0000005848257904	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1929999999999996	0.0000060693474256	0.0000040094279184	0.0000005884278620	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.1940000000000000	0.0000060643474256	0.0000040055736364	0.0000005920177795	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1950000000000003	0.0000060593474256	0.0000040017081234	0.0000005955955899	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.1959999999999997	0.0000060543474256	0.0000039978314445	0.0000005991612769	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.1970000000000001	0.0000060493474256	0.0000039939435130	0.0000006027147188	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.1980000000000004	0.0000060443474256	0.0000039900444757	0.0000006062559558	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.1989999999999998	0.0000060393474256	0.0000039861343393	0.0000006097849309	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.2000000000000002	0.0000060343474256	0.0000039822131105	0.0000006133015869	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.2009999999999996	0.0000060293474256	0.0000039782808658	0.0000006168059156	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2020000000000000	0.0000060243474256	0.0000039743376006	0.0000006202978514	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2029999999999994	0.0000060193474256	0.0000039703834369	0.0000006237774197	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2039999999999997	0.0000060143474256	0.0000039664183013	0.0000006272445046	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.2050000000000001	0.0000060093474256	0.0000039624423383	0.0000006306991488	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2059999999999995	0.0000060043474256	0.0000039584555549	0.0000006341412948	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2069999999999999	0.0000059993474256	0.0000039544579238	0.0000006375708591	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2080000000000002	0.0000059943474256	0.0000039504495662	0.0000006409878685	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2089999999999996	0.0000059893474256	0.0000039464305117	0.0000006443922822	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.2100000000000000	0.0000059843474256	0.0000039424007449	0.0000006477840248	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2110000000000003	0.0000059793474256	0.0000039383603633	0.0000006511631068	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2119999999999997	0.0000059743474256	0.0000039343094081	0.0000006545294958	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2130000000000001	0.0000059693474256	0.0000039302478637	0.0000006578831161	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2139999999999995	0.0000059643474256	0.0000039261758276	0.0000006612239787	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2149999999999999	0.0000059593474256	0.0000039220932732	0.0000006645519988	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.2159999999999993	0.0000059543474256	0.0000039180003534	0.0000006678672316	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2169999999999996	0.0000059493474256	0.0000039138969416	0.0000006711695128	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2180000000000000	0.0000059443474256	0.0000039097832458	0.0000006744589422	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.2189999999999994	0.0000059393474256	0.0000039056592508	0.0000006777354438	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2199999999999998	0.0000059343474256	0.0000039015249200	0.0000006809989225	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2210000000000001	0.0000059293474256	0.0000038973804046	0.0000006842494354	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2219999999999995	0.0000059243474256	0.0000038932257011	0.0000006874869146	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2229999999999999	0.0000059193474256	0.0000038890608170	0.0000006907113005	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2240000000000002	0.0000059143474256	0.0000038848858261	0.0000006939225880	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2249999999999996	0.0000059093474256	0.0000038807008124	0.0000006971207814	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2260000000000000	0.0000059043474256	0.0000038765057183	0.0000007003057663	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2270000000000003	0.0000058993474256	0.0000038723006389	0.0000007034775560	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2279999999999998	0.0000058943474256	0.0000038680856578	0.0000007066361552	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2290000000000001	0.0000058893474256	0.0000038638607398	0.0000007097814674	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.2299999999999995	0.0000058843474256	0.0000038596259898	0.0000007129135157	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2309999999999999	0.0000058793474256	0.0000038553813946	0.0000007160322217	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2319999999999993	0.0000058743474256	0.0000038511270587	0.0000007191376090	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.2329999999999997	0.0000058693474256	0.0000038468629263	0.0000007222295615	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2340000000000000	0.0000058643474256	0.0000038425891444	0.0000007253081406	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2349999999999994	0.0000058593474256	0.0000038383057318	0.0000007283732957	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2359999999999998	0.0000058543474256	0.0000038340126544	0.0000007314249285	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2370000000000001	0.0000058493474256	0.0000038297100374	0.0000007344630826	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2379999999999995	0.0000058443474256	0.0000038253979417	0.0000007374877453	-0.0031415926535900	-0.0000000000000000	0.0000000000000000	
+4.2389999999999999	0.0000058393474256	0.0000038210762814	0.0000007404987699	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2400000000000002	0.0000058343474256	0.0000038167452122	0.0000007434962294	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2409999999999997	0.0000058293474256	0.0000038124048156	0.0000007464801307	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2420000000000000	0.0000058243474256	0.0000038080549859	0.0000007494503069	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2430000000000003	0.0000058193474256	0.0000038036958569	0.0000007524068126	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2439999999999998	0.0000058143474256	0.0000037993275100	0.0000007553496550	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2450000000000001	0.0000058093474256	0.0000037949498819	0.0000007582787048	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2459999999999996	0.0000058043474256	0.0000037905631157	0.0000007611940277	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2469999999999999	0.0000057993474256	0.0000037861671692	0.0000007640955132	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2479999999999993	0.0000057943474256	0.0000037817621848	0.0000007669832281	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2489999999999997	0.0000057893474256	0.0000037773480902	0.0000007698570318	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2500000000000000	0.0000057843474256	0.0000037729250172	0.0000007727169814	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2509999999999994	0.0000057793474256	0.0000037684930155	0.0000007755630553	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2519999999999998	0.0000057743474256	0.0000037640520342	0.0000007783951318	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2530000000000001	0.0000057693474256	0.0000037596022041	0.0000007812132691	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.2539999999999996	0.0000057643474256	0.0000037551435650	0.0000007840174354	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2549999999999999	0.0000057593474256	0.0000037506760966	0.0000007868075387	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2560000000000002	0.0000057543474256	0.0000037461998891	0.0000007895835973	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2569999999999997	0.0000057493474256	0.0000037417150320	0.0000007923456305	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2580000000000000	0.0000057443474256	0.0000037372214658	0.0000007950935050	-0.0031415926535896	0.0000000000000000	0.0000000000000000	
+4.2590000000000003	0.0000057393474256	0.0000037327192999	0.0000007978272601	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2599999999999998	0.0000057343474256	0.0000037282086233	0.0000008005469155	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2610000000000001	0.0000057293474256	0.0000037236893382	0.0000008032522960	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.2619999999999996	0.0000057243474256	0.0000037191616416	0.0000008059435343	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2629999999999999	0.0000057193474256	0.0000037146254754	0.0000008086204958	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2639999999999993	0.0000057143474256	0.0000037100809575	0.0000008112832316	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2649999999999997	0.0000057093474256	0.0000037055280405	0.0000008139316166	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.2660000000000000	0.0000057043474256	0.0000037009668803	0.0000008165657440	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2669999999999995	0.0000056993474256	0.0000036963974491	0.0000008191855096	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2679999999999998	0.0000056943474256	0.0000036918197871	0.0000008217908815	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2690000000000001	0.0000056893474256	0.0000036872339820	0.0000008243818807	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2699999999999996	0.0000056843474256	0.0000036826400926	0.0000008269584970	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.2709999999999999	0.0000056793474256	0.0000036780380732	0.0000008295206038	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2720000000000002	0.0000056743474256	0.0000036734280493	0.0000008320682646	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.2729999999999997	0.0000056693474256	0.0000036688100700	0.0000008346014591	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2740000000000000	0.0000056643474256	0.0000036641841092	0.0000008371200810	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2750000000000004	0.0000056593474256	0.0000036595503010	0.0000008396242058	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.2759999999999998	0.0000056543474256	0.0000036549086381	0.0000008421137487	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2770000000000001	0.0000056493474256	0.0000036502591515	0.0000008445886674	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.2779999999999996	0.0000056443474256	0.0000036456019552	0.0000008470490168	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2789999999999999	0.0000056393474256	0.0000036409369968	0.0000008494946577	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2799999999999994	0.0000056343474256	0.0000036362644452	0.0000008519257103	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2809999999999997	0.0000056293474256	0.0000036315842118	0.0000008543419914	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2820000000000000	0.0000056243474256	0.0000036268964465	0.0000008567436002	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2829999999999995	0.0000056193474256	0.0000036222011800	0.0000008591304949	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.2839999999999998	0.0000056143474256	0.0000036174983798	0.0000008615025566	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2850000000000001	0.0000056093474256	0.0000036127882035	0.0000008638598967	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.2859999999999996	0.0000056043474256	0.0000036080706279	0.0000008662024073	-0.0031415926535896	-0.0000000000000000	-0.0000000000000000	
+4.2869999999999999	0.0000055993474256	0.0000036033457023	0.0000008685300681	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2880000000000003	0.0000055943474256	0.0000035986134936	0.0000008708428812	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.2889999999999997	0.0000055893474256	0.0000035938740684	0.0000008731408489	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2900000000000000	0.0000055843474256	0.0000035891274136	0.0000008754238735	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2910000000000004	0.0000055793474256	0.0000035843736225	0.0000008776919907	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.2919999999999998	0.0000055743474256	0.0000035796127439	0.0000008799451810	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.2930000000000001	0.0000055693474256	0.0000035748447743	0.0000008821833571	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.2939999999999996	0.0000055643474256	0.0000035700698498	0.0000008844066119	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.2949999999999999	0.0000055593474256	0.0000035652879063	0.0000008866147793	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.2959999999999994	0.0000055543474256	0.0000035604991053	0.0000008888079864	-0.0031415926535900	0.0000000000000000	0.0000000000000000	
+4.2969999999999997	0.0000055493474256	0.0000035557033836	0.0000008909860667	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.2980000000000000	0.0000055443474256	0.0000035509008589	0.0000008931490913	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.2989999999999995	0.0000055393474256	0.0000035460916055	0.0000008952970750	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.2999999999999998	0.0000055343474256	0.0000035412755617	0.0000008974298505	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3010000000000002	0.0000055293474256	0.0000035364528866	0.0000008995475467	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.3019999999999996	0.0000055243474256	0.0000035316235781	0.0000009016500760	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3029999999999999	0.0000055193474256	0.0000035267876685	0.0000009037373961	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3040000000000003	0.0000055143474256	0.0000035219452401	0.0000009058095339	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3049999999999997	0.0000055093474256	0.0000035170963331	0.0000009078664589	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.3060000000000000	0.0000055043474256	0.0000035122409717	0.0000009099081176	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3070000000000004	0.0000054993474256	0.0000035073792129	0.0000009119345023	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.3079999999999998	0.0000054943474256	0.0000035025111385	0.0000009139456409	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3090000000000002	0.0000054893474256	0.0000034976367561	0.0000009159414563	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3099999999999996	0.0000054843474256	0.0000034927561390	0.0000009179219649	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3109999999999999	0.0000054793474256	0.0000034878692955	0.0000009198870896	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.3119999999999994	0.0000054743474256	0.0000034829763229	0.0000009218368818	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.3129999999999997	0.0000054693474256	0.0000034780772459	0.0000009237712879	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.3140000000000001	0.0000054643474256	0.0000034731721052	0.0000009256902778	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.3149999999999995	0.0000054593474256	0.0000034682609972	0.0000009275939036	-0.0031415926535896	0.0000000000000000	0.0000000000000000	
+4.3159999999999998	0.0000054543474256	0.0000034633438915	0.0000009294820292	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3170000000000002	0.0000054493474256	0.0000034584208765	0.0000009313546951	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3179999999999996	0.0000054443474256	0.0000034534920480	0.0000009332119545	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3190000000000000	0.0000054393474256	0.0000034485573531	0.0000009350536348	-0.0031415926535897	0.0000000000000000	0.0000000000000000	
+4.3200000000000003	0.0000054343474256	0.0000034436169340	0.0000009368798606	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.3209999999999997	0.0000054293474256	0.0000034386708007	0.0000009386905545	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3220000000000001	0.0000054243474256	0.0000034337189865	0.0000009404856746	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.3230000000000004	0.0000054193474256	0.0000034287615711	0.0000009422652509	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3239999999999998	0.0000054143474256	0.0000034237985953	0.0000009440292537	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.3250000000000002	0.0000054093474256	0.0000034188300778	0.0000009457776171	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3259999999999996	0.0000054043474256	0.0000034138561126	0.0000009475103958	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3270000000000000	0.0000053993474256	0.0000034088767111	0.0000009492275119	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.3279999999999994	0.0000053943474256	0.0000034038919667	0.0000009509290204	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3289999999999997	0.0000053893474256	0.0000033989018763	0.0000009526148191	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3300000000000001	0.0000053843474256	0.0000033939065110	0.0000009542849270	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3309999999999995	0.0000053793474256	0.0000033889059562	0.0000009559393877	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.3319999999999999	0.0000053743474256	0.0000033839001877	0.0000009575780622	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3330000000000002	0.0000053693474256	0.0000033788893127	0.0000009592010308	-0.0031415926535896	0.0000000000000000	-0.0000000000000000	
+4.3339999999999996	0.0000053643474256	0.0000033738733942	0.0000009608083012	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3350000000000000	0.0000053593474256	0.0000033688524019	0.0000009623997217	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3360000000000003	0.0000053543474256	0.0000033638264565	0.0000009639753978	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3369999999999997	0.0000053493474256	0.0000033587955996	0.0000009655353007	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3380000000000001	0.0000053443474256	0.0000033537598376	0.0000009670793396	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.3390000000000004	0.0000053393474256	0.0000033487192619	0.0000009686075719	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3399999999999999	0.0000053343474256	0.0000033436739350	0.0000009701200058	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3409999999999993	0.0000053293474256	0.0000033386238640	0.0000009716165506	-0.0031415926535899	-0.0000000000000000	-0.0000000000000000	
+4.3419999999999996	0.0000053243474256	0.0000033335690911	0.0000009730971774	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3430000000000000	0.0000053193474256	0.0000033285097069	0.0000009745619442	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3439999999999994	0.0000053143474256	0.0000033234457736	0.0000009760108599	-0.0031415926535897	-0.0000000000000000	-0.0000000000000000	
+4.3449999999999998	0.0000053093474256	0.0000033183772721	0.0000009774437837	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.3460000000000001	0.0000053043474256	0.0000033133043126	0.0000009788608117	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3469999999999995	0.0000052993474256	0.0000033082269572	0.0000009802619531	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3479999999999999	0.0000052943474256	0.0000033031451678	0.0000009816470292	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3490000000000002	0.0000052893474256	0.0000032980590739	0.0000009830161744	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3499999999999996	0.0000052843474256	0.0000032929687372	0.0000009843693985	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3510000000000000	0.0000052793474256	0.0000032878741213	0.0000009857065220	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3520000000000003	0.0000052743474256	0.0000032827753671	0.0000009870277058	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3529999999999998	0.0000052693474256	0.0000032776724778	0.0000009883328463	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3540000000000001	0.0000052643474256	0.0000032725654963	0.0000009896219151	-0.0031415926535897	-0.0000000000000000	0.0000000000000000	
+4.3549999999999995	0.0000052593474256	0.0000032674545357	0.0000009908950240	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3559999999999999	0.0000052543474256	0.0000032623395367	0.0000009921519419	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3569999999999993	0.0000052493474256	0.0000032572206755	0.0000009933929078	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3579999999999997	0.0000052443474256	0.0000032520978937	0.0000009946176904	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3590000000000000	0.0000052393474256	0.0000032469713037	0.0000009958264021	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3599999999999994	0.0000052343474256	0.0000032418409666	0.0000009970190539	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3609999999999998	0.0000052293474256	0.0000032367068760	0.0000009981955158	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3620000000000001	0.0000052243474256	0.0000032315691244	0.0000009993558628	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3629999999999995	0.0000052193474256	0.0000032264277790	0.0000010005001190	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3639999999999999	0.0000052143474256	0.0000032212828165	0.0000010016281157	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3650000000000002	0.0000052093474256	0.0000032161343587	0.0000010027399928	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3659999999999997	0.0000052043474256	0.0000032109824486	0.0000010038357234	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3670000000000000	0.0000051993474256	0.0000032058270998	0.0000010049152159	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3680000000000003	0.0000051943474256	0.0000032006683855	0.0000010059785079	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3689999999999998	0.0000051893474256	0.0000031955063783	0.0000010070256372	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3700000000000001	0.0000051843474256	0.0000031903410810	0.0000010080564863	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3709999999999996	0.0000051793474256	0.0000031851726009	0.0000010090711713	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3719999999999999	0.0000051743474256	0.0000031800009184	0.0000010100695226	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3729999999999993	0.0000051693474256	0.0000031748261572	0.0000010110516957	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3739999999999997	0.0000051643474256	0.0000031696483102	0.0000010120175471	-0.0031415926535897	0.0000000000000000	-0.0000000000000000	
+4.3750000000000000	0.0000051593474256	0.0000031644674774	0.0000010129671807	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3759999999999994	0.0000051543474256	0.0000031592836857	0.0000010139005311	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3769999999999998	0.0000051493474256	0.0000031540969628	0.0000010148175330	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3780000000000001	0.0000051443474256	0.0000031489074077	0.0000010157182911	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3789999999999996	0.0000051393474256	0.0000031437150587	0.0000010166027664	-0.0031415926535899	-0.0000000000000000	0.0000000000000000	
+4.3799999999999999	0.0000051343474256	0.0000031385199223	0.0000010174708411	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3810000000000002	0.0000051293474256	0.0000031333221020	0.0000010183226339	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.3819999999999997	0.0000051243474256	0.0000031281216525	0.0000010191581455	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3830000000000000	0.0000051193474256	0.0000031229185704	0.0000010199772317	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3840000000000003	0.0000051143474256	0.0000031177129478	0.0000010207799856	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3849999999999998	0.0000051093474256	0.0000031125048548	0.0000010215664480	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3860000000000001	0.0000051043474256	0.0000031072942742	0.0000010223364347	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3869999999999996	0.0000050993474256	0.0000031020813429	0.0000010230901590	-0.0031415926535899	0.0000000000000000	-0.0000000000000000	
+4.3879999999999999	0.0000050943474256	0.0000030968660392	0.0000010238274232	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.3889999999999993	0.0000050893474256	0.0000030916484635	0.0000010245483486	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3899999999999997	0.0000050843474256	0.0000030864286256	0.0000010252528169	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3910000000000000	0.0000050793474256	0.0000030812066201	0.0000010259409366	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.3919999999999995	0.0000050743474256	0.0000030759824866	0.0000010266126696	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3929999999999998	0.0000050693474256	0.0000030707562459	0.0000010272679246	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3940000000000001	0.0000050643474256	0.0000030655279771	0.0000010279067706	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3949999999999996	0.0000050593474256	0.0000030602977490	0.0000010285292500	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3959999999999999	0.0000050543474256	0.0000030550655593	0.0000010291352047	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.3970000000000002	0.0000050493474256	0.0000030498315054	0.0000010297247579	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.3979999999999997	0.0000050443474256	0.0000030445956414	0.0000010302979125	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.3990000000000000	0.0000050393474256	0.0000030393579806	0.0000010308545504	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4000000000000004	0.0000050343474256	0.0000030341186005	0.0000010313947418	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4009999999999998	0.0000050293474256	0.0000030288775603	0.0000010319185035	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4020000000000001	0.0000050243474256	0.0000030236348830	0.0000010324257445	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.4029999999999996	0.0000050193474256	0.0000030183906587	0.0000010329165761	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4039999999999999	0.0000050143474256	0.0000030131449023	0.0000010333908805	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4049999999999994	0.0000050093474256	0.0000030078976902	0.0000010338487291	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4059999999999997	0.0000050043474256	0.0000030026490509	0.0000010342900443	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4070000000000000	0.0000049993474256	0.0000029973990690	0.0000010347149253	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4079999999999995	0.0000049943474256	0.0000029921477774	0.0000010351233085	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4089999999999998	0.0000049893474256	0.0000029868952222	0.0000010355151710	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4100000000000001	0.0000049843474256	0.0000029816414538	0.0000010358905037	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4109999999999996	0.0000049793474256	0.0000029763865513	0.0000010362493930	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4119999999999999	0.0000049743474256	0.0000029711305282	0.0000010365917075	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4130000000000003	0.0000049693474256	0.0000029658734712	0.0000010369175611	-0.0031415926535899	0.0000000000000000	0.0000000000000000	
+4.4139999999999997	0.0000049643474256	0.0000029606154183	0.0000010372269045	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4150000000000000	0.0000049593474256	0.0000029553563967	0.0000010375196473	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4160000000000004	0.0000049543474256	0.0000029500965072	0.0000010377959590	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4169999999999998	0.0000049493474256	0.0000029448357654	0.0000010380557083	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4180000000000001	0.0000049443474256	0.0000029395742220	0.0000010382988873	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4189999999999996	0.0000049393474256	0.0000029343119650	0.0000010385256251	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4199999999999999	0.0000049343474256	0.0000029290489927	0.0000010387357222	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4209999999999994	0.0000049293474256	0.0000029237854181	0.0000010389294043	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4219999999999997	0.0000049243474256	0.0000029185212300	0.0000010391064305	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4230000000000000	0.0000049193474256	0.0000029132565293	0.0000010392669861	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4239999999999995	0.0000049143474256	0.0000029079913521	0.0000010394110089	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4249999999999998	0.0000049093474256	0.0000029027257385	0.0000010395384508	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4260000000000002	0.0000049043474256	0.0000028974597498	0.0000010396493462	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4269999999999996	0.0000048993474256	0.0000028921934567	0.0000010397437714	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4279999999999999	0.0000048943474256	0.0000028869268661	0.0000010398215403	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4290000000000003	0.0000048893474256	0.0000028816600787	0.0000010398828539	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4299999999999997	0.0000048843474256	0.0000028763931219	0.0000010399276093	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4310000000000000	0.0000048793474256	0.0000028711260400	0.0000010399557727	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4320000000000004	0.0000048743474256	0.0000028658588968	0.0000010399673937	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4329999999999998	0.0000048693474256	0.0000028605917615	0.0000010399625497	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4340000000000002	0.0000048643474256	0.0000028553246445	0.0000010399410550	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4349999999999996	0.0000048593474256	0.0000028500576365	0.0000010399030845	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4359999999999999	0.0000048543474256	0.0000028447907610	0.0000010398485080	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4369999999999994	0.0000048493474256	0.0000028395240957	0.0000010397774456	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4379999999999997	0.0000048443474256	0.0000028342576678	0.0000010396897811	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4390000000000001	0.0000048393474256	0.0000028289915457	0.0000010395855931	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4399999999999995	0.0000048343474256	0.0000028237257829	0.0000010394648912	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4409999999999998	0.0000048293474256	0.0000028184604188	0.0000010393276152	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4420000000000002	0.0000048243474256	0.0000028131955075	0.0000010391737747	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4429999999999996	0.0000048193474256	0.0000028079311266	0.0000010390035052	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4440000000000000	0.0000048143474256	0.0000028026672789	0.0000010388165516	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4450000000000003	0.0000048093474256	0.0000027974040605	0.0000010386131475	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4459999999999997	0.0000048043474256	0.0000027921415088	0.0000010383932194	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4470000000000001	0.0000047993474256	0.0000027868796647	0.0000010381567081	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4480000000000004	0.0000047943474256	0.0000027816185895	0.0000010379036662	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4489999999999998	0.0000047893474256	0.0000027763583509	0.0000010376341888	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4500000000000002	0.0000047843474256	0.0000027710989638	0.0000010373480628	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4509999999999996	0.0000047793474256	0.0000027658405218	0.0000010370455378	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4520000000000000	0.0000047743474256	0.0000027605830341	0.0000010367263588	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4529999999999994	0.0000047693474256	0.0000027553265952	0.0000010363907901	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4539999999999997	0.0000047643474256	0.0000027500712222	0.0000010360386189	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4550000000000001	0.0000047593474256	0.0000027448169863	0.0000010356699695	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4559999999999995	0.0000047543474256	0.0000027395639423	0.0000010352848683	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4569999999999999	0.0000047493474256	0.0000027343121204	0.0000010348831731	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4580000000000002	0.0000047443474256	0.0000027290615966	0.0000010344650511	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4589999999999996	0.0000047393474256	0.0000027238124094	0.0000010340304167	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4600000000000000	0.0000047343474256	0.0000027185646101	0.0000010335792687	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4610000000000003	0.0000047293474256	0.0000027133182595	0.0000010331116766	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4619999999999997	0.0000047243474256	0.0000027080734027	0.0000010326275975	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4630000000000001	0.0000047193474256	0.0000027028300874	0.0000010321270026	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4640000000000004	0.0000047143474256	0.0000026975883736	0.0000010316099619	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4649999999999999	0.0000047093474256	0.0000026923483157	0.0000010310765036	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4660000000000002	0.0000047043474256	0.0000026871099512	0.0000010305265148	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4669999999999996	0.0000046993474256	0.0000026818733478	0.0000010299601369	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4680000000000000	0.0000046943474256	0.0000026766385404	0.0000010293772289	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4689999999999994	0.0000046893474256	0.0000026714056022	0.0000010287779893	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4699999999999998	0.0000046843474256	0.0000026661745582	0.0000010281621786	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4710000000000001	0.0000046793474256	0.0000026609454822	0.0000010275300098	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4719999999999995	0.0000046743474256	0.0000026557184219	0.0000010268814557	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4729999999999999	0.0000046693474256	0.0000026504934172	0.0000010262164046	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4740000000000002	0.0000046643474256	0.0000026452705304	0.0000010255349712	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4749999999999996	0.0000046593474256	0.0000026400498123	0.0000010248371572	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4760000000000000	0.0000046543474256	0.0000026348313089	0.0000010241229080	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4770000000000003	0.0000046493474256	0.0000026296150776	0.0000010233922964	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4779999999999998	0.0000046443474256	0.0000026244011692	0.0000010226453248	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4790000000000001	0.0000046393474256	0.0000026191896259	0.0000010218818824	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4799999999999995	0.0000046343474256	0.0000026139805172	0.0000010211022129	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4809999999999999	0.0000046293474256	0.0000026087738733	0.0000010203060356	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4819999999999993	0.0000046243474256	0.0000026035697652	0.0000010194936373	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4829999999999997	0.0000046193474256	0.0000025983682267	0.0000010186647661	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4840000000000000	0.0000046143474256	0.0000025931693229	0.0000010178196382	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4849999999999994	0.0000046093474256	0.0000025879731001	0.0000010169581865	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4859999999999998	0.0000046043474256	0.0000025827796061	0.0000010160803581	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4870000000000001	0.0000045993474256	0.0000025775888975	0.0000010151862566	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4879999999999995	0.0000045943474256	0.0000025724010257	0.0000010142759005	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4889999999999999	0.0000045893474256	0.0000025672160344	0.0000010133491382	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4900000000000002	0.0000045843474256	0.0000025620339831	0.0000010124061591	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4909999999999997	0.0000045793474256	0.0000025568549211	0.0000010114469399	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4920000000000000	0.0000045743474256	0.0000025516788957	0.0000010104713861	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4930000000000003	0.0000045693474256	0.0000025465059610	0.0000010094795886	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.4939999999999998	0.0000045643474256	0.0000025413361688	0.0000010084715814	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.4950000000000001	0.0000045593474256	0.0000025361695678	0.0000010074472992	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.4959999999999996	0.0000045543474256	0.0000025310062111	0.0000010064068333	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4969999999999999	0.0000045493474256	0.0000025258461480	0.0000010053501190	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4979999999999993	0.0000045443474256	0.0000025206894304	0.0000010042772196	-0.0031415926535898	-0.0000000000000000	0.0000000000000000	
+4.4989999999999997	0.0000045393474256	0.0000025155361081	0.0000010031880708	-0.0031415926535898	0.0000000000000000	-0.0000000000000000	
+4.5000000000000000	0.0000045343474256	0.0000025103862335	0.0000010020827789	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.5009999999999994	0.0000045293474256	0.0000025052398569	0.0000010009613653	-0.0031415926535898	-0.0000000000000000	-0.0000000000000000	
+4.5019999999999998	0.0000045243474256	0.0000025000970283	0.0000009998236810	-0.0031415926535898	0.0000000000000000	0.0000000000000000	
+4.5030000000000001	0.0000045193474256	0.0000024949577993	0.0000009986699041	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5039999999999996	0.0000045143474256	0.0000024929577993	0.0000009896699282	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5049999999999999	0.0000045093474256	0.0000024909577993	0.0000009806699097	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5060000000000002	0.0000045043474256	0.0000024889577993	0.0000009716698912	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5069999999999997	0.0000044993474256	0.0000024869577993	0.0000009626699580	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5080000000000000	0.0000044943474256	0.0000024849577993	0.0000009536698826	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5090000000000003	0.0000044893474256	0.0000024829577993	0.0000009446699067	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5099999999999998	0.0000044843474256	0.0000024809577993	0.0000009356699309	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5110000000000001	0.0000044793474256	0.0000024789577993	0.0000009266699124	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5119999999999996	0.0000044743474256	0.0000024769577993	0.0000009176699365	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5129999999999999	0.0000044693474256	0.0000024749577993	0.0000009086699038	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5139999999999993	0.0000044643474256	0.0000024729577993	0.0000008996699421	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5149999999999997	0.0000044593474256	0.0000024709577993	0.0000008906698952	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5160000000000000	0.0000044543474256	0.0000024689577993	0.0000008816699051	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5169999999999995	0.0000044493474256	0.0000024669577993	0.0000008726699576	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5179999999999998	0.0000044443474256	0.0000024649577993	0.0000008636698965	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5190000000000001	0.0000044393474256	0.0000024629577993	0.0000008546698922	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5199999999999996	0.0000044343474256	0.0000024609577993	0.0000008456699447	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5209999999999999	0.0000044293474256	0.0000024589577993	0.0000008366698978	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5220000000000002	0.0000044243474256	0.0000024569577993	0.0000008276699219	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5229999999999997	0.0000044193474256	0.0000024549577993	0.0000008186699176	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5240000000000000	0.0000044143474256	0.0000024529577993	0.0000008096699133	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5250000000000004	0.0000044093474256	0.0000024509577993	0.0000008006698948	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5259999999999998	0.0000044043474256	0.0000024489577993	0.0000007916699616	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5270000000000001	0.0000043993474256	0.0000024469577993	0.0000007826698862	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5279999999999996	0.0000043943474256	0.0000024449577993	0.0000007736699388	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5289999999999999	0.0000043893474256	0.0000024429577993	0.0000007646699061	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5299999999999994	0.0000043843474256	0.0000024409577993	0.0000007556699444	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5309999999999997	0.0000043793474256	0.0000024389577993	0.0000007466699117	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5320000000000000	0.0000043743474256	0.0000024369577993	0.0000007376698790	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5329999999999995	0.0000043693474256	0.0000024349577993	0.0000007286699599	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5339999999999998	0.0000043643474256	0.0000024329577993	0.0000007196698988	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5350000000000001	0.0000043593474256	0.0000024309577993	0.0000007106698945	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5359999999999996	0.0000043543474256	0.0000024289577993	0.0000007016699470	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5369999999999999	0.0000043493474256	0.0000024269577993	0.0000006926699143	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5380000000000003	0.0000043443474256	0.0000024249577993	0.0000006836699100	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5389999999999997	0.0000043393474256	0.0000024229577993	0.0000006746699341	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5400000000000000	0.0000043343474256	0.0000024209577993	0.0000006656699014	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5410000000000004	0.0000043293474256	0.0000024189577993	0.0000006566698829	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5419999999999998	0.0000043243474256	0.0000024169577993	0.0000006476699497	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5430000000000001	0.0000043193474256	0.0000024149577993	0.0000006386699170	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5439999999999996	0.0000043143474256	0.0000024129577993	0.0000006296699269	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5449999999999999	0.0000043093474256	0.0000024109577993	0.0000006206698941	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5459999999999994	0.0000043043474256	0.0000024089577993	0.0000006116699467	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5469999999999997	0.0000042993474256	0.0000024069577993	0.0000006026698998	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5480000000000000	0.0000042943474256	0.0000024049577993	0.0000005936698955	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5489999999999995	0.0000042893474256	0.0000024029577993	0.0000005846699480	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5499999999999998	0.0000042843474256	0.0000024009577993	0.0000005756699153	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5510000000000002	0.0000042793474256	0.0000023989577993	0.0000005666698826	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5519999999999996	0.0000042743474256	0.0000023969577993	0.0000005576699351	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5529999999999999	0.0000042693474256	0.0000023949577993	0.0000005486699024	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5540000000000003	0.0000042643474256	0.0000023929577993	0.0000005396699123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5549999999999997	0.0000042593474256	0.0000023909577993	0.0000005306699364	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5560000000000000	0.0000042543474256	0.0000023889577993	0.0000005216699179	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5570000000000004	0.0000042493474256	0.0000023869577993	0.0000005126698994	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5579999999999998	0.0000042443474256	0.0000023849577993	0.0000005036699235	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5590000000000002	0.0000042393474256	0.0000023829577993	0.0000004946699050	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5599999999999996	0.0000042343474256	0.0000023809577993	0.0000004856699434	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5609999999999999	0.0000042293474256	0.0000023789577993	0.0000004766699107	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5619999999999994	0.0000042243474256	0.0000023769577993	0.0000004676699490	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5629999999999997	0.0000042193474256	0.0000023749577993	0.0000004586698878	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5640000000000001	0.0000042143474256	0.0000023729577993	0.0000004496698978	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5649999999999995	0.0000042093474256	0.0000023709577993	0.0000004406699503	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5659999999999998	0.0000042043474256	0.0000023689577993	0.0000004316699034	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5670000000000002	0.0000041993474256	0.0000023669577993	0.0000004226699133	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5679999999999996	0.0000041943474256	0.0000023649577993	0.0000004136699232	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5690000000000000	0.0000041893474256	0.0000023629577993	0.0000004046699047	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5700000000000003	0.0000041843474256	0.0000023609577993	0.0000003956699146	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5709999999999997	0.0000041793474256	0.0000023589577993	0.0000003866699387	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5720000000000001	0.0000041743474256	0.0000023569577993	0.0000003776699060	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5730000000000004	0.0000041693474256	0.0000023549577993	0.0000003686699017	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5739999999999998	0.0000041643474256	0.0000023529577993	0.0000003596699401	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5750000000000002	0.0000041593474256	0.0000023509577993	0.0000003506699073	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5759999999999996	0.0000041543474256	0.0000023489577993	0.0000003416699457	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5770000000000000	0.0000041493474256	0.0000023469577993	0.0000003326698987	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5779999999999994	0.0000041443474256	0.0000023449577993	0.0000003236699229	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5789999999999997	0.0000041393474256	0.0000023429577993	0.0000003146699186	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5800000000000001	0.0000041343474256	0.0000023409577993	0.0000003056698858	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5809999999999995	0.0000041293474256	0.0000023389577993	0.0000002966699384	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5819999999999999	0.0000041243474256	0.0000023369577993	0.0000002876699057	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5830000000000002	0.0000041193474256	0.0000023349577993	0.0000002786699156	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5839999999999996	0.0000041143474256	0.0000023329577993	0.0000002696699397	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5850000000000000	0.0000041093474256	0.0000023309577993	0.0000002606698928	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5860000000000003	0.0000041043474256	0.0000023289577993	0.0000002516698885	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5869999999999997	0.0000040993474256	0.0000023269577993	0.0000002426699552	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5880000000000001	0.0000040943474256	0.0000023249577993	0.0000002336698941	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5890000000000004	0.0000040893474256	0.0000023229577993	0.0000002246699040	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5899999999999999	0.0000040843474256	0.0000023209577993	0.0000002156699423	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5910000000000002	0.0000040793474256	0.0000023189577993	0.0000002066698954	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5919999999999996	0.0000040743474256	0.0000023169577993	0.0000001976699480	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5930000000000000	0.0000040693474256	0.0000023149577993	0.0000001886699152	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5939999999999994	0.0000040643474256	0.0000023129577993	0.0000001796699252	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5949999999999998	0.0000040593474256	0.0000023109577993	0.0000001706699067	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5960000000000001	0.0000040543474256	0.0000023089577993	0.0000001616699024	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5969999999999995	0.0000040493474256	0.0000023069577993	0.0000001526699407	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5979999999999999	0.0000040443474256	0.0000023049577993	0.0000001436698938	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5990000000000002	0.0000040393474256	0.0000023029577993	0.0000001346699037	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.5999999999999996	0.0000040343474256	0.0000023009577993	0.0000001256699420	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6010000000000000	0.0000040293474256	0.0000022989577993	0.0000001166698951	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6020000000000003	0.0000040243474256	0.0000022969577993	0.0000001076699050	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6029999999999998	0.0000040193474256	0.0000022949577993	0.0000000986699433	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6040000000000001	0.0000040143474256	0.0000022929577993	0.0000000896699106	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6049999999999995	0.0000040093474256	0.0000022909577993	0.0000000806699347	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6059999999999999	0.0000040043474256	0.0000022889577993	0.0000000716699162	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6069999999999993	0.0000039993474256	0.0000022869577993	0.0000000626699403	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6079999999999997	0.0000039943474256	0.0000022849577993	0.0000000536698934	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6090000000000000	0.0000039893474256	0.0000022829577993	0.0000000446699033	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6099999999999994	0.0000039843474256	0.0000022809577993	0.0000000356699417	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6109999999999998	0.0000039793474256	0.0000022789577993	0.0000000266699089	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6120000000000001	0.0000039743474256	0.0000022769577993	0.0000000176699047	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6129999999999995	0.0000039693474256	0.0000022749577993	0.0000000086699430	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6139999999999999	0.0000039643474256	0.0000022729577993	-0.0000000003300897	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6150000000000002	0.0000039593474256	0.0000022709577993	-0.0000000093301082	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6159999999999997	0.0000039543474256	0.0000022689577993	-0.0000000183300557	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6170000000000000	0.0000039493474256	0.0000022669577993	-0.0000000273300884	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6180000000000003	0.0000039443474256	0.0000022649577993	-0.0000000363301069	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6189999999999998	0.0000039393474256	0.0000022629577993	-0.0000000453300686	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6200000000000001	0.0000039343474256	0.0000022609577993	-0.0000000543300871	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6209999999999996	0.0000039293474256	0.0000022589577993	-0.0000000633300630	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6219999999999999	0.0000039243474256	0.0000022569577993	-0.0000000723300957	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6229999999999993	0.0000039193474256	0.0000022549577993	-0.0000000813300716	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6239999999999997	0.0000039143474256	0.0000022529577993	-0.0000000903300901	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6250000000000000	0.0000039093474256	0.0000022509577993	-0.0000000993300944	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6259999999999994	0.0000039043474256	0.0000022489577993	-0.0000001083300702	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6269999999999998	0.0000038993474256	0.0000022469577993	-0.0000001173300888	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6280000000000001	0.0000038943474256	0.0000022449577993	-0.0000001263300931	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6289999999999996	0.0000038893474256	0.0000022429577993	-0.0000001353300547	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6299999999999999	0.0000038843474256	0.0000022409577993	-0.0000001443301016	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6310000000000002	0.0000038793474256	0.0000022389577993	-0.0000001533301202	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6319999999999997	0.0000038743474256	0.0000022369577993	-0.0000001623300534	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6330000000000000	0.0000038693474256	0.0000022349577993	-0.0000001713300861	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6340000000000003	0.0000038643474256	0.0000022329577993	-0.0000001803301046	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6349999999999998	0.0000038593474256	0.0000022309577993	-0.0000001893300521	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6360000000000001	0.0000038543474256	0.0000022289577993	-0.0000001983301132	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6369999999999996	0.0000038493474256	0.0000022269577993	-0.0000002073300465	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6379999999999999	0.0000038443474256	0.0000022249577993	-0.0000002163300934	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6389999999999993	0.0000038393474256	0.0000022229577993	-0.0000002253300835	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6399999999999997	0.0000038343474256	0.0000022209577993	-0.0000002343300878	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6410000000000000	0.0000038293474256	0.0000022189577993	-0.0000002433300921	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6419999999999995	0.0000038243474256	0.0000022169577993	-0.0000002523300537	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6429999999999998	0.0000038193474256	0.0000022149577993	-0.0000002613301007	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6440000000000001	0.0000038143474256	0.0000022129577993	-0.0000002703301050	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6449999999999996	0.0000038093474256	0.0000022109577993	-0.0000002793300524	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6459999999999999	0.0000038043474256	0.0000022089577993	-0.0000002883300851	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6470000000000002	0.0000037993474256	0.0000022069577993	-0.0000002973301036	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6479999999999997	0.0000037943474256	0.0000022049577993	-0.0000003063300511	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6490000000000000	0.0000037893474256	0.0000022029577993	-0.0000003153300980	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6500000000000004	0.0000037843474256	0.0000022009577993	-0.0000003243301023	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6509999999999998	0.0000037793474256	0.0000021989577993	-0.0000003333300640	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6520000000000001	0.0000037743474256	0.0000021969577993	-0.0000003423300967	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6529999999999996	0.0000037693474256	0.0000021949577993	-0.0000003513300442	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6539999999999999	0.0000037643474256	0.0000021929577993	-0.0000003603301053	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6549999999999994	0.0000037593474256	0.0000021909577993	-0.0000003693300528	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6559999999999997	0.0000037543474256	0.0000021889577993	-0.0000003783301139	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6570000000000000	0.0000037493474256	0.0000021869577993	-0.0000003873300898	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6579999999999995	0.0000037443474256	0.0000021849577993	-0.0000003963300514	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6589999999999998	0.0000037393474256	0.0000021829577993	-0.0000004053300984	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6600000000000001	0.0000037343474256	0.0000021809577993	-0.0000004143301169	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6609999999999996	0.0000037293474256	0.0000021789577993	-0.0000004233300501	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6619999999999999	0.0000037243474256	0.0000021769577993	-0.0000004323300971	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6630000000000003	0.0000037193474256	0.0000021749577993	-0.0000004413300871	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6639999999999997	0.0000037143474256	0.0000021729577993	-0.0000004503300772	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6650000000000000	0.0000037093474256	0.0000021709577993	-0.0000004593300957	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6660000000000004	0.0000037043474256	0.0000021689577993	-0.0000004683301000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6669999999999998	0.0000036993474256	0.0000021669577993	-0.0000004773300617	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6680000000000001	0.0000036943474256	0.0000021649577993	-0.0000004863301086	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6689999999999996	0.0000036893474256	0.0000021629577993	-0.0000004953300419	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6699999999999999	0.0000036843474256	0.0000021609577993	-0.0000005043300888	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6709999999999994	0.0000036793474256	0.0000021589577993	-0.0000005133300647	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6719999999999997	0.0000036743474256	0.0000021569577993	-0.0000005223301116	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6730000000000000	0.0000036693474256	0.0000021549577993	-0.0000005313301017	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6739999999999995	0.0000036643474256	0.0000021529577993	-0.0000005403300491	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6749999999999998	0.0000036593474256	0.0000021509577993	-0.0000005493301103	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6760000000000002	0.0000036543474256	0.0000021489577993	-0.0000005583300862	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6769999999999996	0.0000036493474256	0.0000021469577993	-0.0000005673300478	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6779999999999999	0.0000036443474256	0.0000021449577993	-0.0000005763300948	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6790000000000003	0.0000036393474256	0.0000021429577993	-0.0000005853301133	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6799999999999997	0.0000036343474256	0.0000021409577993	-0.0000005943300607	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6810000000000000	0.0000036293474256	0.0000021389577993	-0.0000006033300934	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6820000000000004	0.0000036243474256	0.0000021369577993	-0.0000006123300835	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6829999999999998	0.0000036193474256	0.0000021349577993	-0.0000006213300594	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6840000000000002	0.0000036143474256	0.0000021329577993	-0.0000006303301205	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6849999999999996	0.0000036093474256	0.0000021309577993	-0.0000006393300396	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6859999999999999	0.0000036043474256	0.0000021289577993	-0.0000006483301007	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6869999999999994	0.0000035993474256	0.0000021269577993	-0.0000006573300482	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6879999999999997	0.0000035943474256	0.0000021249577993	-0.0000006663301093	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6890000000000001	0.0000035893474256	0.0000021229577993	-0.0000006753300852	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6899999999999995	0.0000035843474256	0.0000021209577993	-0.0000006843300611	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6909999999999998	0.0000035793474256	0.0000021189577993	-0.0000006933301080	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6920000000000002	0.0000035743474256	0.0000021169577993	-0.0000007023300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6929999999999996	0.0000035693474256	0.0000021149577993	-0.0000007113300597	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6940000000000000	0.0000035643474256	0.0000021129577993	-0.0000007203300925	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6950000000000003	0.0000035593474256	0.0000021109577993	-0.0000007293301110	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6959999999999997	0.0000035543474256	0.0000021089577993	-0.0000007383300442	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6970000000000001	0.0000035493474256	0.0000021069577993	-0.0000007473301054	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6980000000000004	0.0000035443474256	0.0000021049577993	-0.0000007563301097	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.6989999999999998	0.0000035393474256	0.0000021029577993	-0.0000007653300429	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7000000000000002	0.0000035343474256	0.0000021009577993	-0.0000007743301182	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7009999999999996	0.0000035293474256	0.0000020989577993	-0.0000007833300515	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7020000000000000	0.0000035243474256	0.0000020969577993	-0.0000007923300984	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7029999999999994	0.0000035193474256	0.0000020949577993	-0.0000008013300459	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7039999999999997	0.0000035143474256	0.0000020929577993	-0.0000008103301070	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7050000000000001	0.0000035093474256	0.0000020909577993	-0.0000008193301113	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7059999999999995	0.0000035043474256	0.0000020889577993	-0.0000008283300446	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7069999999999999	0.0000034993474256	0.0000020869577993	-0.0000008373301057	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7080000000000002	0.0000034943474256	0.0000020849577993	-0.0000008463300958	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7089999999999996	0.0000034893474256	0.0000020829577993	-0.0000008553300574	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7100000000000000	0.0000034843474256	0.0000020809577993	-0.0000008643301044	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7110000000000003	0.0000034793474256	0.0000020789577993	-0.0000008733300945	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7119999999999997	0.0000034743474256	0.0000020769577993	-0.0000008823300561	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7130000000000001	0.0000034693474256	0.0000020749577993	-0.0000008913301173	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7140000000000004	0.0000034643474256	0.0000020729577993	-0.0000009003300789	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7149999999999999	0.0000034593474256	0.0000020709577993	-0.0000009093300548	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7160000000000002	0.0000034543474256	0.0000020689577993	-0.0000009183301017	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7169999999999996	0.0000034493474256	0.0000020669577993	-0.0000009273300634	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7180000000000000	0.0000034443474256	0.0000020649577993	-0.0000009363300819	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7189999999999994	0.0000034393474256	0.0000020629577993	-0.0000009453300578	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7199999999999998	0.0000034343474256	0.0000020609577993	-0.0000009543301047	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7210000000000001	0.0000034293474256	0.0000020589577993	-0.0000009633300948	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7219999999999995	0.0000034243474256	0.0000020569577993	-0.0000009723300565	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7229999999999999	0.0000034193474256	0.0000020549577993	-0.0000009813300892	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7240000000000002	0.0000034143474256	0.0000020529577993	-0.0000009903301077	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7249999999999996	0.0000034093474256	0.0000020509577993	-0.0000009993300552	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7260000000000000	0.0000034043474256	0.0000020489577993	-0.0000010083301021	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7270000000000003	0.0000033993474256	0.0000020469577993	-0.0000010173300922	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7279999999999998	0.0000033943474256	0.0000020449577993	-0.0000010263300538	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7290000000000001	0.0000033893474256	0.0000020429577993	-0.0000010353301150	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7299999999999995	0.0000033843474256	0.0000020409577993	-0.0000010443300340	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7309999999999999	0.0000033793474256	0.0000020389577993	-0.0000010533301094	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7319999999999993	0.0000033743474256	0.0000020369577993	-0.0000010623300426	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7329999999999997	0.0000033693474256	0.0000020349577993	-0.0000010713301180	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7340000000000000	0.0000033643474256	0.0000020329577993	-0.0000010803300938	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7349999999999994	0.0000033593474256	0.0000020309577993	-0.0000010893300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7359999999999998	0.0000033543474256	0.0000020289577993	-0.0000010983300882	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7370000000000001	0.0000033493474256	0.0000020269577993	-0.0000011073301067	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7379999999999995	0.0000033443474256	0.0000020249577993	-0.0000011163300684	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7389999999999999	0.0000033393474256	0.0000020229577993	-0.0000011253301011	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7400000000000002	0.0000033343474256	0.0000020209577993	-0.0000011343300912	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7409999999999997	0.0000033293474256	0.0000020189577993	-0.0000011433300671	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7420000000000000	0.0000033243474256	0.0000020169577993	-0.0000011523301140	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7430000000000003	0.0000033193474256	0.0000020149577993	-0.0000011613300757	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7439999999999998	0.0000033143474256	0.0000020129577993	-0.0000011703300657	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7450000000000001	0.0000033093474256	0.0000020109577993	-0.0000011793300985	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7459999999999996	0.0000033043474256	0.0000020089577993	-0.0000011883300601	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7469999999999999	0.0000032993474256	0.0000020069577993	-0.0000011973300929	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7479999999999993	0.0000032943474256	0.0000020049577993	-0.0000012063300687	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7489999999999997	0.0000032893474256	0.0000020029577993	-0.0000012153301014	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7500000000000000	0.0000032843474256	0.0000020009577993	-0.0000012243300915	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7509999999999994	0.0000032793474256	0.0000019989577993	-0.0000012333300532	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7519999999999998	0.0000032743474256	0.0000019969577993	-0.0000012423301001	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7530000000000001	0.0000032693474256	0.0000019949577993	-0.0000012513300902	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7539999999999996	0.0000032643474256	0.0000019929577993	-0.0000012603300661	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7549999999999999	0.0000032593474256	0.0000019909577993	-0.0000012693300988	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7560000000000002	0.0000032543474256	0.0000019889577993	-0.0000012783301031	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7569999999999997	0.0000032493474256	0.0000019869577993	-0.0000012873300506	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7580000000000000	0.0000032443474256	0.0000019849577993	-0.0000012963300975	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7590000000000003	0.0000032393474256	0.0000019829577993	-0.0000013053301018	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7599999999999998	0.0000032343474256	0.0000019809577993	-0.0000013143300492	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7610000000000001	0.0000032293474256	0.0000019789577993	-0.0000013233301104	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7619999999999996	0.0000032243474256	0.0000019769577993	-0.0000013323300578	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7629999999999999	0.0000032193474256	0.0000019749577993	-0.0000013413300906	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7639999999999993	0.0000032143474256	0.0000019729577993	-0.0000013503300522	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7649999999999997	0.0000032093474256	0.0000019709577993	-0.0000013593300991	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7660000000000000	0.0000032043474256	0.0000019689577993	-0.0000013683301034	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7669999999999995	0.0000031993474256	0.0000019669577993	-0.0000013773300509	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7679999999999998	0.0000031943474256	0.0000019649577993	-0.0000013863300978	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7690000000000001	0.0000031893474256	0.0000019629577993	-0.0000013953300879	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7699999999999996	0.0000031843474256	0.0000019609577993	-0.0000014043300638	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7709999999999999	0.0000031793474256	0.0000019589577993	-0.0000014133301107	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7720000000000002	0.0000031743474256	0.0000019569577993	-0.0000014223301008	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7729999999999997	0.0000031693474256	0.0000019549577993	-0.0000014313300341	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7740000000000000	0.0000031643474256	0.0000019529577993	-0.0000014403301236	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7750000000000004	0.0000031593474256	0.0000019509577993	-0.0000014493300995	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7759999999999998	0.0000031543474256	0.0000019489577993	-0.0000014583300469	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7770000000000001	0.0000031493474256	0.0000019469577993	-0.0000014673301081	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7779999999999996	0.0000031443474256	0.0000019449577993	-0.0000014763300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7789999999999999	0.0000031393474256	0.0000019429577993	-0.0000014853300883	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7799999999999994	0.0000031343474256	0.0000019409577993	-0.0000014943300641	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7809999999999997	0.0000031293474256	0.0000019389577993	-0.0000015033300826	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7820000000000000	0.0000031243474256	0.0000019369577993	-0.0000015123301011	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7829999999999995	0.0000031193474256	0.0000019349577993	-0.0000015213300628	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7839999999999998	0.0000031143474256	0.0000019329577993	-0.0000015303300955	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7850000000000001	0.0000031093474256	0.0000019309577993	-0.0000015393300998	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7859999999999996	0.0000031043474256	0.0000019289577993	-0.0000015483300615	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7869999999999999	0.0000030993474256	0.0000019269577993	-0.0000015573300942	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7880000000000003	0.0000030943474256	0.0000019249577993	-0.0000015663301127	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7889999999999997	0.0000030893474256	0.0000019229577993	-0.0000015753300460	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7900000000000000	0.0000030843474256	0.0000019209577993	-0.0000015843300929	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7910000000000004	0.0000030793474256	0.0000019189577993	-0.0000015933301114	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7919999999999998	0.0000030743474256	0.0000019169577993	-0.0000016023300589	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7930000000000001	0.0000030693474256	0.0000019149577993	-0.0000016113300774	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7939999999999996	0.0000030643474256	0.0000019129577993	-0.0000016203300675	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7949999999999999	0.0000030593474256	0.0000019109577993	-0.0000016293301002	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7959999999999994	0.0000030543474256	0.0000019089577993	-0.0000016383300618	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7969999999999997	0.0000030493474256	0.0000019069577993	-0.0000016473300946	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7980000000000000	0.0000030443474256	0.0000019049577993	-0.0000016563300989	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7989999999999995	0.0000030393474256	0.0000019029577993	-0.0000016653300605	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.7999999999999998	0.0000030343474256	0.0000019009577993	-0.0000016743300932	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8010000000000002	0.0000030293474256	0.0000018989577993	-0.0000016833300975	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8019999999999996	0.0000030243474256	0.0000018969577993	-0.0000016923300592	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8029999999999999	0.0000030193474256	0.0000018949577993	-0.0000017013300919	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8040000000000003	0.0000030143474256	0.0000018929577993	-0.0000017103301104	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8049999999999997	0.0000030093474256	0.0000018909577993	-0.0000017193300437	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8060000000000000	0.0000030043474256	0.0000018889577993	-0.0000017283301048	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8070000000000004	0.0000029993474256	0.0000018869577993	-0.0000017373300949	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8079999999999998	0.0000029943474256	0.0000018849577993	-0.0000017463300566	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8090000000000002	0.0000029893474256	0.0000018829577993	-0.0000017553300893	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8099999999999996	0.0000029843474256	0.0000018809577993	-0.0000017643300509	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8109999999999999	0.0000029793474256	0.0000018789577993	-0.0000017733300979	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8119999999999994	0.0000029743474256	0.0000018769577993	-0.0000017823300595	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8129999999999997	0.0000029693474256	0.0000018749577993	-0.0000017913301065	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8140000000000001	0.0000029643474256	0.0000018729577993	-0.0000018003301108	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8149999999999995	0.0000029593474256	0.0000018709577993	-0.0000018093300440	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8159999999999998	0.0000029543474256	0.0000018689577993	-0.0000018183301052	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8170000000000002	0.0000029493474256	0.0000018669577993	-0.0000018273300952	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8179999999999996	0.0000029443474256	0.0000018649577993	-0.0000018363300711	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8190000000000000	0.0000029393474256	0.0000018629577993	-0.0000018453300896	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8200000000000003	0.0000029343474256	0.0000018609577993	-0.0000018543301081	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8209999999999997	0.0000029293474256	0.0000018589577993	-0.0000018633300556	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8220000000000001	0.0000029243474256	0.0000018569577993	-0.0000018723301025	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8230000000000004	0.0000029193474256	0.0000018549577993	-0.0000018813300926	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8239999999999998	0.0000029143474256	0.0000018529577993	-0.0000018903300543	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8250000000000002	0.0000029093474256	0.0000018509577993	-0.0000018993301012	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8259999999999996	0.0000029043474256	0.0000018489577993	-0.0000019083300486	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8270000000000000	0.0000028993474256	0.0000018469577993	-0.0000019173301098	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8279999999999994	0.0000028943474256	0.0000018449577993	-0.0000019263300572	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8289999999999997	0.0000028893474256	0.0000018429577993	-0.0000019353301042	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8300000000000001	0.0000028843474256	0.0000018409577993	-0.0000019443300943	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8309999999999995	0.0000028793474256	0.0000018389577993	-0.0000019533300559	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8319999999999999	0.0000028743474256	0.0000018369577993	-0.0000019623301029	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8330000000000002	0.0000028693474256	0.0000018349577993	-0.0000019713300787	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8339999999999996	0.0000028643474256	0.0000018329577993	-0.0000019803300688	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8350000000000000	0.0000028593474256	0.0000018309577993	-0.0000019893301015	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8360000000000003	0.0000028543474256	0.0000018289577993	-0.0000019983301058	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8369999999999997	0.0000028493474256	0.0000018269577993	-0.0000020073300391	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8380000000000001	0.0000028443474256	0.0000018249577993	-0.0000020163301002	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8390000000000004	0.0000028393474256	0.0000018229577993	-0.0000020253301045	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8399999999999999	0.0000028343474256	0.0000018209577993	-0.0000020343300662	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8410000000000002	0.0000028293474256	0.0000018189577993	-0.0000020433300989	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8419999999999996	0.0000028243474256	0.0000018169577993	-0.0000020523300321	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8430000000000000	0.0000028193474256	0.0000018149577993	-0.0000020613301075	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8439999999999994	0.0000028143474256	0.0000018129577993	-0.0000020703300692	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8449999999999998	0.0000028093474256	0.0000018109577993	-0.0000020793300877	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8460000000000001	0.0000028043474256	0.0000018089577993	-0.0000020883300920	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8469999999999995	0.0000027993474256	0.0000018069577993	-0.0000020973300536	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8479999999999999	0.0000027943474256	0.0000018049577993	-0.0000021063301148	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8490000000000002	0.0000027893474256	0.0000018029577993	-0.0000021153301049	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8499999999999996	0.0000027843474256	0.0000018009577993	-0.0000021243300523	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8510000000000000	0.0000027793474256	0.0000017989577993	-0.0000021333300992	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8520000000000003	0.0000027743474256	0.0000017969577993	-0.0000021423300893	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8529999999999998	0.0000027693474256	0.0000017949577993	-0.0000021513300794	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8540000000000001	0.0000027643474256	0.0000017929577993	-0.0000021603300837	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8549999999999995	0.0000027593474256	0.0000017909577993	-0.0000021693300596	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8559999999999999	0.0000027543474256	0.0000017889577993	-0.0000021783300923	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8569999999999993	0.0000027493474256	0.0000017869577993	-0.0000021873300682	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8579999999999997	0.0000027443474256	0.0000017849577993	-0.0000021963300867	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8590000000000000	0.0000027393474256	0.0000017829577993	-0.0000022053301194	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8599999999999994	0.0000027343474256	0.0000017809577993	-0.0000022143300527	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8609999999999998	0.0000027293474256	0.0000017789577993	-0.0000022233300996	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8620000000000001	0.0000027243474256	0.0000017769577993	-0.0000022323301039	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8629999999999995	0.0000027193474256	0.0000017749577993	-0.0000022413300371	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8639999999999999	0.0000027143474256	0.0000017729577993	-0.0000022503301125	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8650000000000002	0.0000027093474256	0.0000017709577993	-0.0000022593301026	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8659999999999997	0.0000027043474256	0.0000017689577993	-0.0000022683300500	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8670000000000000	0.0000026993474256	0.0000017669577993	-0.0000022773300969	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8680000000000003	0.0000026943474256	0.0000017649577993	-0.0000022863300870	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8689999999999998	0.0000026893474256	0.0000017629577993	-0.0000022953300771	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8700000000000001	0.0000026843474256	0.0000017609577993	-0.0000023043300956	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8709999999999996	0.0000026793474256	0.0000017589577993	-0.0000023133300573	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8719999999999999	0.0000026743474256	0.0000017569577993	-0.0000023223300900	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8729999999999993	0.0000026693474256	0.0000017549577993	-0.0000023313300659	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8739999999999997	0.0000026643474256	0.0000017529577993	-0.0000023403300986	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8750000000000000	0.0000026593474256	0.0000017509577993	-0.0000023493300887	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8759999999999994	0.0000026543474256	0.0000017489577993	-0.0000023583300504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8769999999999998	0.0000026493474256	0.0000017469577993	-0.0000023673301115	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8780000000000001	0.0000026443474256	0.0000017449577993	-0.0000023763300874	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8789999999999996	0.0000026393474256	0.0000017429577993	-0.0000023853300632	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8799999999999999	0.0000026343474256	0.0000017409577993	-0.0000023943300960	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8810000000000002	0.0000026293474256	0.0000017389577993	-0.0000024033301145	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8819999999999997	0.0000026243474256	0.0000017369577993	-0.0000024123300335	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8830000000000000	0.0000026193474256	0.0000017349577993	-0.0000024213301089	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8840000000000003	0.0000026143474256	0.0000017329577993	-0.0000024303300989	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8849999999999998	0.0000026093474256	0.0000017309577993	-0.0000024393300464	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8860000000000001	0.0000026043474256	0.0000017289577993	-0.0000024483301075	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8869999999999996	0.0000025993474256	0.0000017269577993	-0.0000024573300550	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8879999999999999	0.0000025943474256	0.0000017249577993	-0.0000024663300877	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8889999999999993	0.0000025893474256	0.0000017229577993	-0.0000024753300778	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8899999999999997	0.0000025843474256	0.0000017209577993	-0.0000024843300963	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8910000000000000	0.0000025793474256	0.0000017189577993	-0.0000024933300864	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8919999999999995	0.0000025743474256	0.0000017169577993	-0.0000025023300623	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8929999999999998	0.0000025693474256	0.0000017149577993	-0.0000025113301092	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8940000000000001	0.0000025643474256	0.0000017129577993	-0.0000025203300993	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8949999999999996	0.0000025593474256	0.0000017109577993	-0.0000025293300610	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8959999999999999	0.0000025543474256	0.0000017089577993	-0.0000025383300937	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8970000000000002	0.0000025493474256	0.0000017069577993	-0.0000025473300980	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8979999999999997	0.0000025443474256	0.0000017049577993	-0.0000025563300738	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.8990000000000000	0.0000025393474256	0.0000017029577993	-0.0000025653300924	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9000000000000004	0.0000025343474256	0.0000017009577993	-0.0000025743300966	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9009999999999998	0.0000025293474256	0.0000016989577993	-0.0000025833300583	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9020000000000001	0.0000025243474256	0.0000016969577993	-0.0000025923301052	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9029999999999996	0.0000025193474256	0.0000016949577993	-0.0000026013300527	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9039999999999999	0.0000025143474256	0.0000016929577993	-0.0000026103300854	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9049999999999994	0.0000025093474256	0.0000016909577993	-0.0000026193300755	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9059999999999997	0.0000025043474256	0.0000016889577993	-0.0000026283300940	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9070000000000000	0.0000024993474256	0.0000016869577993	-0.0000026373300841	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9079999999999995	0.0000024943474256	0.0000016849577993	-0.0000026463300600	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9089999999999998	0.0000024893474256	0.0000016829577993	-0.0000026553300927	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9100000000000001	0.0000024843474256	0.0000016809577993	-0.0000026643301112	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9109999999999996	0.0000024793474256	0.0000016789577993	-0.0000026733300587	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9119999999999999	0.0000024743474256	0.0000016769577993	-0.0000026823300914	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9130000000000003	0.0000024693474256	0.0000016749577993	-0.0000026913301099	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9139999999999997	0.0000024643474256	0.0000016729577993	-0.0000027003300573	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9150000000000000	0.0000024593474256	0.0000016709577993	-0.0000027093300901	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9160000000000004	0.0000024543474256	0.0000016689577993	-0.0000027183300944	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9169999999999998	0.0000024493474256	0.0000016669577993	-0.0000027273300560	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9180000000000001	0.0000024443474256	0.0000016649577993	-0.0000027363301029	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9189999999999996	0.0000024393474256	0.0000016629577993	-0.0000027453300504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9199999999999999	0.0000024343474256	0.0000016609577993	-0.0000027543300973	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9209999999999994	0.0000024293474256	0.0000016589577993	-0.0000027633300590	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9219999999999997	0.0000024243474256	0.0000016569577993	-0.0000027723300917	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9230000000000000	0.0000024193474256	0.0000016549577993	-0.0000027813300960	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9239999999999995	0.0000024143474256	0.0000016529577993	-0.0000027903300577	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9249999999999998	0.0000024093474256	0.0000016509577993	-0.0000027993301046	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9260000000000002	0.0000024043474256	0.0000016489577993	-0.0000028083301089	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9269999999999996	0.0000023993474256	0.0000016469577993	-0.0000028173300564	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9279999999999999	0.0000023943474256	0.0000016449577993	-0.0000028263301033	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9290000000000003	0.0000023893474256	0.0000016429577993	-0.0000028353300792	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9299999999999997	0.0000023843474256	0.0000016409577993	-0.0000028443300693	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9310000000000000	0.0000023793474256	0.0000016389577993	-0.0000028533301020	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9320000000000004	0.0000023743474257	0.0000016369577993	-0.0000028623300921	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9329999999999998	0.0000023693474256	0.0000016349577993	-0.0000028713300537	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9340000000000002	0.0000023643474256	0.0000016329577993	-0.0000028803301007	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9349999999999996	0.0000023593474256	0.0000016309577993	-0.0000028893300623	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9359999999999999	0.0000023543474256	0.0000016289577993	-0.0000028983301092	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9369999999999994	0.0000023493474256	0.0000016269577993	-0.0000029073300567	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9379999999999997	0.0000023443474256	0.0000016249577993	-0.0000029163300894	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9390000000000001	0.0000023393474256	0.0000016229577993	-0.0000029253301079	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9399999999999995	0.0000023343474256	0.0000016209577993	-0.0000029343300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9409999999999998	0.0000023293474256	0.0000016189577993	-0.0000029433301023	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9420000000000002	0.0000023243474256	0.0000016169577993	-0.0000029523301066	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9429999999999996	0.0000023193474256	0.0000016149577993	-0.0000029613300683	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9440000000000000	0.0000023143474256	0.0000016129577993	-0.0000029703300868	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9450000000000003	0.0000023093474256	0.0000016109577993	-0.0000029793301053	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9459999999999997	0.0000023043474256	0.0000016089577993	-0.0000029883300527	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9470000000000001	0.0000022993474256	0.0000016069577993	-0.0000029973301139	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9480000000000004	0.0000022943474256	0.0000016049577993	-0.0000030063300898	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9489999999999998	0.0000022893474256	0.0000016029577993	-0.0000030153300372	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9500000000000002	0.0000022843474256	0.0000016009577993	-0.0000030243301126	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9509999999999996	0.0000022793474256	0.0000015989577993	-0.0000030333300600	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9520000000000000	0.0000022743474256	0.0000015969577993	-0.0000030423300785	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9529999999999994	0.0000022693474256	0.0000015949577993	-0.0000030513300686	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9539999999999997	0.0000022643474256	0.0000015929577993	-0.0000030603300871	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9550000000000001	0.0000022593474256	0.0000015909577993	-0.0000030693301198	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9559999999999995	0.0000022543474256	0.0000015889577993	-0.0000030783300531	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9569999999999999	0.0000022493474256	0.0000015869577993	-0.0000030873301000	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9580000000000002	0.0000022443474256	0.0000015849577993	-0.0000030963300901	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9589999999999996	0.0000022393474256	0.0000015829577993	-0.0000031053300660	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9600000000000000	0.0000022343474256	0.0000015809577993	-0.0000031143300845	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9610000000000003	0.0000022293474257	0.0000015789577993	-0.0000031233301030	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9619999999999997	0.0000022243474256	0.0000015769577993	-0.0000031323300504	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9630000000000001	0.0000022193474256	0.0000015749577993	-0.0000031413300974	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9640000000000004	0.0000022143474256	0.0000015729577993	-0.0000031503301159	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9649999999999999	0.0000022093474256	0.0000015709577993	-0.0000031593300491	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9660000000000002	0.0000022043474256	0.0000015689577993	-0.0000031683300961	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9669999999999996	0.0000021993474256	0.0000015669577993	-0.0000031773300577	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9680000000000000	0.0000021943474256	0.0000015649577993	-0.0000031863301189	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9689999999999994	0.0000021893474256	0.0000015629577993	-0.0000031953300379	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9699999999999998	0.0000021843474256	0.0000015609577993	-0.0000032043300990	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9710000000000001	0.0000021793474256	0.0000015589577993	-0.0000032133301175	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9719999999999995	0.0000021743474256	0.0000015569577993	-0.0000032223300508	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9729999999999999	0.0000021693474256	0.0000015549577993	-0.0000032313300977	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9740000000000002	0.0000021643474256	0.0000015529577993	-0.0000032403300878	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9749999999999996	0.0000021593474256	0.0000015509577993	-0.0000032493300637	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9760000000000000	0.0000021543474256	0.0000015489577993	-0.0000032583301106	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9770000000000003	0.0000021493474256	0.0000015469577993	-0.0000032673300865	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9779999999999998	0.0000021443474256	0.0000015449577993	-0.0000032763300624	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9790000000000001	0.0000021393474256	0.0000015429577993	-0.0000032853300951	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9800000000000004	0.0000021343474256	0.0000015409577993	-0.0000032943300994	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9809999999999999	0.0000021293474256	0.0000015389577993	-0.0000033033300610	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9819999999999993	0.0000021243474256	0.0000015369577993	-0.0000033123300511	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9829999999999997	0.0000021193474256	0.0000015349577993	-0.0000033213300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9840000000000000	0.0000021143474256	0.0000015329577993	-0.0000033303301166	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9849999999999994	0.0000021093474256	0.0000015309577993	-0.0000033393300498	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9859999999999998	0.0000021043474256	0.0000015289577993	-0.0000033483300967	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9870000000000001	0.0000020993474256	0.0000015269577993	-0.0000033573300868	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9879999999999995	0.0000020943474256	0.0000015249577993	-0.0000033663300627	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9889999999999999	0.0000020893474256	0.0000015229577993	-0.0000033753300954	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9900000000000002	0.0000020843474257	0.0000015209577993	-0.0000033843300997	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9909999999999997	0.0000020793474256	0.0000015189577993	-0.0000033933300614	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9920000000000000	0.0000020743474256	0.0000015169577993	-0.0000034023300941	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9930000000000003	0.0000020693474256	0.0000015149577993	-0.0000034113300984	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9939999999999998	0.0000020643474256	0.0000015129577993	-0.0000034203300601	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9950000000000001	0.0000020593474256	0.0000015109577993	-0.0000034293300928	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9959999999999996	0.0000020543474256	0.0000015089577993	-0.0000034383300687	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9969999999999999	0.0000020493474256	0.0000015069577993	-0.0000034473300730	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9979999999999993	0.0000020443474256	0.0000015049577993	-0.0000034563300630	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+4.9989999999999997	0.0000020393474256	0.0000015029577993	-0.0000034653300958	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0000000000000000	0.0000020343474256	0.0000015009577993	-0.0000034743301143	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0009999999999994	0.0000020293474256	0.0000014989577993	-0.0000034833300617	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0019999999999998	0.0000020243474256	0.0000014969577993	-0.0000034923300802	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0030000000000001	0.0000020193474256	0.0000014949577993	-0.0000035013300987	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0039999999999996	0.0000020143474256	0.0000014929577993	-0.0000035103300604	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0049999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0060000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0069999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0080000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0090000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0099999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0110000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0119999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300839	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0129999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0140000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0149999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0160000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0169999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0179999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0190000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0199999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0209999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0220000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0229999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0240000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0250000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0259999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0270000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0279999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0289999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0300000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0309999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0320000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0329999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0339999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0350000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0359999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0369999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0380000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0389999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0400000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0410000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0419999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0430000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0439999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0449999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0459999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0469999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0480000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0489999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0499999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0510000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0519999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0529999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0540000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300839	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0549999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0560000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0569999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0579999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0590000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300839	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0599999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300839	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0609999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0619999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0629999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0640000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0649999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0659999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0670000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0679999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0690000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0700000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0709999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0720000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0729999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0739999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0750000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0759999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0770000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0779999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300839	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0789999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0800000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0809999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0819999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0830000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0839999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0850000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0860000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0869999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0880000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0889999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0899999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0910000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0919999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0930000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0939999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0949999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0960000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0969999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0979999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0990000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.0999999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1010000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1020000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1029999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1040000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1049999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300555	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1059999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1070000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1079999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1090000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1099999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1109999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300839	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1120000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301123	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1129999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1139999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1150000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1159999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1170000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1180000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1189999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1200000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1209999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1219999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1230000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1239999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1250000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1259999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1269999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1280000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1289999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1299999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1310000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1319999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1330000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1340000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1349999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1360000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1369999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1379999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1390000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1399999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1410000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1419999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1429999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1440000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1449999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1459999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1470000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1479999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1490000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1500000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1509999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1520000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1529999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1539999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1550000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1559999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1570000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1579999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1589999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1600000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1609999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1619999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1630000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1639999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1650000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1660000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1669999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1680000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1689999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1699999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1710000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1719999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1730000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1739999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1749999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1760000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1769999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1779999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1790000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1799999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1810000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1819999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1829999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1840000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1849999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1859999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1869999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1879999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1890000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1899999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1909999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1920000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1929999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1940000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1950000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1959999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1970000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1979999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.1989999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2000000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2009999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2020000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2029999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2039999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2050000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2059999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2069999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2080000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2089999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2100000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2110000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2119999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2130000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2139999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2149999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2160000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2169999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2180000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2189999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2199999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2210000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2219999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2229999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2240000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2249999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2260000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2270000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2279999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2290000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2299999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2309999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2320000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2329999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300128	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2340000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2349999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2359999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2370000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2379999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2389999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2400000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2409999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2420000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2430000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2439999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2450000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2459999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2469999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2480000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2489999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2500000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2509999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2519999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2530000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2539999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2549999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2560000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2569999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2580000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2590000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2599999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2610000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2619999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2629999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2640000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2649999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2660000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2669999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2679999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2690000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2699999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2709999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2720000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2729999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2740000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2750000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2759999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2770000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2779999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2789999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2800000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2809999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2820000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2829999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2839999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2850000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2859999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2869999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2880000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2889999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2900000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2910000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2919999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2930000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2939999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2949999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2960000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2969999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2980000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2989999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.2999999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3010000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3019999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3029999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3040000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3049999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3060000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3069999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3079999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3090000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3099999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3109999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3119999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3129999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3140000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3149999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3159999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3170000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3179999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3190000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3200000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3209999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3220000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3229999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3239999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3250000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3259999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3270000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3279999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3289999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3300000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3309999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3319999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3330000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3339999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3350000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3360000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3369999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3380000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3389999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3399999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3410000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3419999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3430000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3439999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3449999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3460000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3469999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3479999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3490000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3499999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3510000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3520000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3529999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3540000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3549999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3559999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3570000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3579999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3590000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3599999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3609999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3620000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3629999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3639999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3650000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3659999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3670000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3680000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3689999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3700000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3709999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3719999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3730000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3739999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3750000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3759999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3769999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3780000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3789999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3799999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3810000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3819999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3830000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3840000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3849999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3860000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3869999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3879999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3890000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3899999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3910000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3919999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3929999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3940000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3949999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3959999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3970000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3979999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.3990000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4000000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4009999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4020000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4029999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4039999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4050000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4059999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4070000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4079999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4089999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4100000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4109999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4119999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4130000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4139999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4150000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4160000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4169999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4180000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4189999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4199999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4210000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4219999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4230000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4239999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4249999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4260000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4269999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4279999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4290000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4299999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4310000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4319999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4329999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4340000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4349999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4359999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4369999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4379999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4390000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4399999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4409999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4420000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4429999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4440000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4450000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4459999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4470000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4479999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4489999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4500000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4509999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4520000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4529999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4539999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4550000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4559999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4569999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4580000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4589999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4600000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4610000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4619999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4630000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4639999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4649999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4660000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4669999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4680000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4689999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4699999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4710000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4719999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4729999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4740000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4749999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4760000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4770000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4779999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4790000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4799999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4809999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4820000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4829999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4840000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4849999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4859999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4870000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4879999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4889999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4900000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4909999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4920000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4930000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4939999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4950000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4959999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4969999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4980000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.4989999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5000000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5009999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5019999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5030000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5039999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5049999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5060000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5069999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5080000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5090000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5099999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5110000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5119999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5129999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5140000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5149999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5160000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5169999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5179999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5190000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5199999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5209999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5220000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5229999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5240000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5250000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5259999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5270000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5279999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5289999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5300000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5309999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5320000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5329999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5339999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5350000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5359999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5369999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5380000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5389999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5400000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5409999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5419999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5430000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5439999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5449999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5460000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5469999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5480000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5489999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5499999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5510000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5519999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5529999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5540000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5549999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5560000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5569999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5579999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5590000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5599999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5609999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5620000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5629999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5640000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5649999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5659999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5670000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5679999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5690000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5700000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5709999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5720000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5729999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5739999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5750000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5759999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5770000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5780000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5789999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5800000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5809999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5819999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5830000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5839999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5850000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5860000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5869999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5880000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5889999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5899999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5910000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5919999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5930000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5939999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5949999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5960000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5969999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5979999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5990000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.5999999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6010000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6020000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6029999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6040000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6049999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6059999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6070000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6079999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6090000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6099999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6109999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6120000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6129999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6139999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6150000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6159999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6170000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6180000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6189999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6200000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6209999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6219999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6230000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6239999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6250000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6259999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6269999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6280000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6289999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6299999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6310000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6319999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6330000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6340000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6349999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6360000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6369999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6379999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6390000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6399999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6410000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6419999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6429999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6440000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6449999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6459999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6470000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6479999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6490000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6500000000000004	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6509999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6520000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6529999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6539999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6550000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6559999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6570000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6579999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6589999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6600000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6609999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6619999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6630000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6639999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6650000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6659999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6669999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6680000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6689999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6699999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6710000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6719999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6730000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6739999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6749999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6760000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6769999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6779999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6790000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6799999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6810000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6819999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6829999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6840000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6849999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6859999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6870000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6879999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6890000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6899999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6909999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6920000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6929999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6940000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6950000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6959999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6970000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6979999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.6989999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7000000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7009999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7020000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7030000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7039999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7050000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7059999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7069999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7080000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7089999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7100000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7110000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7119999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7130000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7139999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7149999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7160000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7169999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7180000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7189999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7199999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7210000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7219999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7229999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7240000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7249999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7260000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7270000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7279999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7290000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7299999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7309999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7320000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7329999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7340000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7349999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7359999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7370000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7379999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7389999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7400000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7409999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7420000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7430000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7439999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7450000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7459999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7469999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7480000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7489999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7500000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7509999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7519999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7530000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7539999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7549999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7560000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7569999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7580000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7590000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7599999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7610000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7619999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7629999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7640000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7649999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7660000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7669999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7679999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7690000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7699999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7709999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7720000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7729999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7740000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7749999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7759999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7770000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7779999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7789999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7800000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7809999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7820000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7829999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7839999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7850000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7859999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7869999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7880000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7889999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7900000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7909999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7919999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7930000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7939999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7949999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7960000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7969999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7980000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7989999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.7999999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8010000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8019999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8029999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8040000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8049999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8060000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8069999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8079999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8090000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8099999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8109999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8120000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8129999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8140000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8149999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8159999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8170000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8179999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8190000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8200000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8209999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8220000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8229999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8239999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8250000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8259999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8270000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8280000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8289999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8300000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8309999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8319999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8330000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8339999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8350000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8360000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8369999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8380000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8389999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8399999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8410000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8419999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8430000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8440000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8449999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8460000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8469999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8479999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8490000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8499999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8510000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8520000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8529999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8540000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8549999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8559999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8570000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8579999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8590000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8600000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8609999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8620000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8629999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8639999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8650000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8659999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8670000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8680000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8689999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8700000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8709999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8719999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8730000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8739999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8750000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8759999999999994	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8769999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8780000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8789999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8799999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8810000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8819999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8830000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8840000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8849999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8860000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8869999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8879999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8890000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8899999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8910000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8919999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8929999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8940000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8949999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8959999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8970000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8979999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8990000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.8999999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9009999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9020000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9029999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9039999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9050000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9059999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9070000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9079999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9089999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9100000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9109999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9119999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9130000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9139999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9150000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9159999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9169999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9180000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9189999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9199999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9210000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9219999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9230000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9239999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300128	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9249999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9260000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9269999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9279999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9290000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9299999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9310000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9319999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9329999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9340000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9349999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9359999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9370000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9379999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9390000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9399999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9409999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9420000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9429999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9440000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9450000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9459999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9470000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9479999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300128	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9489999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9500000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9509999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9520000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9530000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9539999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9550000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9559999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9569999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9580000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9589999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9600000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9610000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9619999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9630000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9639999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9649999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9660000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9669999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9680000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9690000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9699999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9710000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9719999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9729999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9740000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9749999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9760000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9770000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9779999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9790000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9799999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9809999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9820000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9829999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9840000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9850000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9859999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9870000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9879999999999995	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9889999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9900000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301549	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9909999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9920000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9930000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9939999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9950000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9959999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9969999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9980000000000002	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+5.9989999999999997	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+6.0000000000000000	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+6.0010000000000003	0.0000020118474256	0.0000014919577993	-0.0000035148301265	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+6.0019999999999998	0.0000020118474256	0.0000014919577993	-0.0000035148300412	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+6.0030000000000001	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+6.0039999999999996	0.0000020118474256	0.0000014919577993	-0.0000035148300981	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
+6.0049999999999999	0.0000020118474256	0.0000014919577993	-0.0000035148300697	0.0000000000000000	-0.0000000000000000	0.0000000000000000	
diff --git a/src/test/data/IMU/odom_pure_translation.txt b/src/test/data/IMU/odom_pure_translation.txt
new file mode 100644
index 0000000000000000000000000000000000000000..17669dc5b60458fd91b99a12554c9e600f30a2c9
--- /dev/null
+++ b/src/test/data/IMU/odom_pure_translation.txt
@@ -0,0 +1,2000 @@
+0.005	0.00499998	0.00999983	0.00999983	0	0	0	
+0.01	0.00499985	0.00999883	0.00999883	0	0	0	
+0.015	0.0049996	0.00999683	0.00999683	0	0	0	
+0.02	0.00499923	0.00999383	0.00999383	0	0	0	
+0.025	0.00499873	0.00998984	0.00998984	0	0	0	
+0.03	0.0049981	0.00998484	0.00998484	0	0	0	
+0.035	0.00499735	0.00997884	0.00997884	0	0	0	
+0.04	0.00499648	0.00997185	0.00997185	0	0	0	
+0.045	0.00499548	0.00996386	0.00996386	0	0	0	
+0.05	0.00499436	0.00995487	0.00995487	0	0	0	
+0.055	0.00499311	0.00994488	0.00994488	0	0	0	
+0.06	0.00499173	0.00993391	0.00993391	0	0	0	
+0.065	0.00499023	0.00992194	0.00992194	0	0	0	
+0.07	0.00498861	0.00990897	0.00990897	0	0	0	
+0.075	0.00498686	0.00989502	0.00989502	0	0	0	
+0.08	0.00498499	0.00988007	0.00988007	0	0	0	
+0.085	0.00498299	0.00986414	0.00986414	0	0	0	
+0.09	0.00498087	0.00984722	0.00984722	0	0	0	
+0.095	0.00497862	0.00982932	0.00982932	0	0	0	
+0.1	0.00497625	0.00981044	0.00981044	0	0	0	
+0.105	0.00497375	0.00979057	0.00979057	0	0	0	
+0.11	0.00497113	0.00976972	0.00976972	0	0	0	
+0.115	0.00496839	0.0097479	0.0097479	0	0	0	
+0.12	0.00496552	0.0097251	0.0097251	0	0	0	
+0.125	0.00496253	0.00970133	0.00970133	0	0	0	
+0.13	0.00495941	0.00967659	0.00967659	0	0	0	
+0.135	0.00495617	0.00965088	0.00965088	0	0	0	
+0.14	0.0049528	0.00962421	0.00962421	0	0	0	
+0.145	0.00494932	0.00959658	0.00959658	0	0	0	
+0.15	0.0049457	0.00956798	0.00956798	0	0	0	
+0.155	0.00494197	0.00953843	0.00953843	0	0	0	
+0.16	0.00493811	0.00950792	0.00950792	0	0	0	
+0.165	0.00493412	0.00947647	0.00947647	0	0	0	
+0.17	0.00493002	0.00944406	0.00944406	0	0	0	
+0.175	0.00492579	0.00941072	0.00941072	0	0	0	
+0.18	0.00492144	0.00937643	0.00937643	0	0	0	
+0.185	0.00491696	0.0093412	0.0093412	0	0	0	
+0.19	0.00491236	0.00930504	0.00930504	0	0	0	
+0.195	0.00490764	0.00926795	0.00926795	0	0	0	
+0.2	0.0049028	0.00922993	0.00922993	0	0	0	
+0.205	0.00489783	0.00919099	0.00919099	0	0	0	
+0.21	0.00489274	0.00915113	0.00915113	0	0	0	
+0.215	0.00488753	0.00911035	0.00911035	0	0	0	
+0.22	0.00488219	0.00906866	0.00906866	0	0	0	
+0.225	0.00487674	0.00902607	0.00902607	0	0	0	
+0.23	0.00487116	0.00898257	0.00898257	0	0	0	
+0.235	0.00486546	0.00893818	0.00893818	0	0	0	
+0.24	0.00485964	0.00889289	0.00889289	0	0	0	
+0.245	0.0048537	0.00884671	0.00884671	0	0	0	
+0.25	0.00484763	0.00879965	0.00879965	0	0	0	
+0.255	0.00484145	0.00875171	0.00875171	0	0	0	
+0.26	0.00483514	0.00870289	0.00870289	0	0	0	
+0.265	0.00482872	0.0086532	0.0086532	0	0	0	
+0.27	0.00482217	0.00860265	0.00860265	0	0	0	
+0.275	0.0048155	0.00855124	0.00855124	0	0	0	
+0.28	0.00480871	0.00849897	0.00849897	0	0	0	
+0.285	0.0048018	0.00844585	0.00844585	0	0	0	
+0.29	0.00479477	0.00839189	0.00839189	0	0	0	
+0.295	0.00478763	0.00833709	0.00833709	0	0	0	
+0.3	0.00478036	0.00828145	0.00828145	0	0	0	
+0.305	0.00477297	0.00822499	0.00822499	0	0	0	
+0.31	0.00476546	0.0081677	0.0081677	0	0	0	
+0.315	0.00475783	0.0081096	0.0081096	0	0	0	
+0.32	0.00475009	0.00805068	0.00805068	0	0	0	
+0.325	0.00474223	0.00799096	0.00799096	0	0	0	
+0.33	0.00473424	0.00793045	0.00793045	0	0	0	
+0.335	0.00472614	0.00786914	0.00786914	0	0	0	
+0.34	0.00471792	0.00780704	0.00780704	0	0	0	
+0.345	0.00470959	0.00774416	0.00774416	0	0	0	
+0.35	0.00470113	0.00768051	0.00768051	0	0	0	
+0.355	0.00469256	0.00761608	0.00761608	0	0	0	
+0.36	0.00468387	0.0075509	0.0075509	0	0	0	
+0.365	0.00467506	0.00748496	0.00748496	0	0	0	
+0.37	0.00466614	0.00741828	0.00741828	0	0	0	
+0.375	0.0046571	0.00735085	0.00735085	0	0	0	
+0.38	0.00464794	0.00728269	0.00728269	0	0	0	
+0.385	0.00463867	0.00721379	0.00721379	0	0	0	
+0.39	0.00462928	0.00714418	0.00714418	0	0	0	
+0.395	0.00461977	0.00707385	0.00707385	0	0	0	
+0.4	0.00461015	0.00700282	0.00700282	0	0	0	
+0.405	0.00460042	0.00693108	0.00693108	0	0	0	
+0.41	0.00459057	0.00685866	0.00685866	0	0	0	
+0.415	0.0045806	0.00678554	0.00678554	0	0	0	
+0.42	0.00457052	0.00671175	0.00671175	0	0	0	
+0.425	0.00456033	0.00663729	0.00663729	0	0	0	
+0.43	0.00455002	0.00656216	0.00656216	0	0	0	
+0.435	0.0045396	0.00648637	0.00648637	0	0	0	
+0.44	0.00452906	0.00640994	0.00640994	0	0	0	
+0.445	0.00451842	0.00633287	0.00633287	0	0	0	
+0.45	0.00450765	0.00625516	0.00625516	0	0	0	
+0.455	0.00449678	0.00617683	0.00617683	0	0	0	
+0.46	0.00448579	0.00609788	0.00609788	0	0	0	
+0.465	0.00447469	0.00601832	0.00601832	0	0	0	
+0.47	0.00446348	0.00593816	0.00593816	0	0	0	
+0.475	0.00445216	0.0058574	0.0058574	0	0	0	
+0.48	0.00444073	0.00577606	0.00577606	0	0	0	
+0.485	0.00442918	0.00569415	0.00569415	0	0	0	
+0.49	0.00441753	0.00561166	0.00561166	0	0	0	
+0.495	0.00440576	0.00552861	0.00552861	0	0	0	
+0.5	0.00439389	0.00544501	0.00544501	0	0	0	
+0.505	0.0043819	0.00536086	0.00536086	0	0	0	
+0.51	0.00436981	0.00527618	0.00527618	0	0	0	
+0.515	0.0043576	0.00519097	0.00519097	0	0	0	
+0.52	0.00434529	0.00510524	0.00510524	0	0	0	
+0.525	0.00433287	0.005019	0.005019	0	0	0	
+0.53	0.00432034	0.00493226	0.00493226	0	0	0	
+0.535	0.0043077	0.00484502	0.00484502	0	0	0	
+0.54	0.00429495	0.0047573	0.0047573	0	0	0	
+0.545	0.0042821	0.00466911	0.00466911	0	0	0	
+0.55	0.00426914	0.00458045	0.00458045	0	0	0	
+0.555	0.00425607	0.00449133	0.00449133	0	0	0	
+0.56	0.0042429	0.00440176	0.00440176	0	0	0	
+0.565	0.00422962	0.00431175	0.00431175	0	0	0	
+0.57	0.00421623	0.00422131	0.00422131	0	0	0	
+0.575	0.00420274	0.00413044	0.00413044	0	0	0	
+0.58	0.00418915	0.00403917	0.00403917	0	0	0	
+0.585	0.00417545	0.00394749	0.00394749	0	0	0	
+0.59	0.00416164	0.00385541	0.00385541	0	0	0	
+0.595	0.00414773	0.00376295	0.00376295	0	0	0	
+0.6	0.00413372	0.00367012	0.00367012	0	0	0	
+0.605	0.0041196	0.00357692	0.00357692	0	0	0	
+0.61	0.00410538	0.00348335	0.00348335	0	0	0	
+0.615	0.00409106	0.00338945	0.00338945	0	0	0	
+0.62	0.00407664	0.0032952	0.0032952	0	0	0	
+0.625	0.00406211	0.00320062	0.00320062	0	0	0	
+0.63	0.00404749	0.00310572	0.00310572	0	0	0	
+0.635	0.00403276	0.00301051	0.00301051	0	0	0	
+0.64	0.00401793	0.002915	0.002915	0	0	0	
+0.645	0.004003	0.0028192	0.0028192	0	0	0	
+0.65	0.00398797	0.00272312	0.00272312	0	0	0	
+0.655	0.00397284	0.00262677	0.00262677	0	0	0	
+0.66	0.00395761	0.00253015	0.00253015	0	0	0	
+0.665	0.00394228	0.00243328	0.00243328	0	0	0	
+0.67	0.00392685	0.00233616	0.00233616	0	0	0	
+0.675	0.00391133	0.00223882	0.00223882	0	0	0	
+0.68	0.00389571	0.00214124	0.00214124	0	0	0	
+0.685	0.00387999	0.00204346	0.00204346	0	0	0	
+0.69	0.00386417	0.00194547	0.00194547	0	0	0	
+0.695	0.00384826	0.00184728	0.00184728	0	0	0	
+0.7	0.00383225	0.00174892	0.00174892	0	0	0	
+0.705	0.00381614	0.00165037	0.00165037	0	0	0	
+0.71	0.00379994	0.00155166	0.00155166	0	0	0	
+0.715	0.00378365	0.0014528	0.0014528	0	0	0	
+0.72	0.00376726	0.00135379	0.00135379	0	0	0	
+0.725	0.00375077	0.00125464	0.00125464	0	0	0	
+0.73	0.00373419	0.00115537	0.00115537	0	0	0	
+0.735	0.00371752	0.00105599	0.00105599	0	0	0	
+0.74	0.00370076	0.000956495	0.000956495	0	0	0	
+0.745	0.0036839	0.000856908	0.000856908	0	0	0	
+0.75	0.00366695	0.000757235	0.000757235	0	0	0	
+0.755	0.00364991	0.000657486	0.000657486	0	0	0	
+0.76	0.00363278	0.000557671	0.000557671	0	0	0	
+0.765	0.00361555	0.000457801	0.000457801	0	0	0	
+0.77	0.00359824	0.000357885	0.000357885	0	0	0	
+0.775	0.00358084	0.000257934	0.000257934	0	0	0	
+0.78	0.00356334	0.000157956	0.000157956	0	0	0	
+0.785	0.00354576	5.79627e-05	5.79627e-05	0	0	0	
+0.79	0.00352809	-4.20364e-05	-4.20364e-05	0	0	0	
+0.795	0.00351033	-0.000142031	-0.000142031	0	0	0	
+0.8	0.00349249	-0.000242012	-0.000242012	0	0	0	
+0.805	0.00347455	-0.000341969	-0.000341969	0	0	0	
+0.81	0.00345653	-0.000441891	-0.000441891	0	0	0	
+0.815	0.00343842	-0.000541769	-0.000541769	0	0	0	
+0.82	0.00342023	-0.000641593	-0.000641593	0	0	0	
+0.825	0.00340195	-0.000741353	-0.000741353	0	0	0	
+0.83	0.00338359	-0.000841039	-0.000841039	0	0	0	
+0.835	0.00336514	-0.00094064	-0.00094064	0	0	0	
+0.84	0.00334661	-0.00104015	-0.00104015	0	0	0	
+0.845	0.00332799	-0.00113955	-0.00113955	0	0	0	
+0.85	0.00330929	-0.00123884	-0.00123884	0	0	0	
+0.855	0.00329051	-0.00133801	-0.00133801	0	0	0	
+0.86	0.00327165	-0.00143704	-0.00143704	0	0	0	
+0.865	0.0032527	-0.00153593	-0.00153593	0	0	0	
+0.87	0.00323367	-0.00163466	-0.00163466	0	0	0	
+0.875	0.00321457	-0.00173323	-0.00173323	0	0	0	
+0.88	0.00319538	-0.00183163	-0.00183163	0	0	0	
+0.885	0.00317611	-0.00192984	-0.00192984	0	0	0	
+0.89	0.00315676	-0.00202787	-0.00202787	0	0	0	
+0.895	0.00313733	-0.00212568	-0.00212568	0	0	0	
+0.9	0.00311783	-0.00222329	-0.00222329	0	0	0	
+0.905	0.00309825	-0.00232068	-0.00232068	0	0	0	
+0.91	0.00307858	-0.00241783	-0.00241783	0	0	0	
+0.915	0.00305885	-0.00251474	-0.00251474	0	0	0	
+0.92	0.00303903	-0.0026114	-0.0026114	0	0	0	
+0.925	0.00301914	-0.00270779	-0.00270779	0	0	0	
+0.93	0.00299918	-0.00280392	-0.00280392	0	0	0	
+0.935	0.00297914	-0.00289977	-0.00289977	0	0	0	
+0.94	0.00295902	-0.00299532	-0.00299532	0	0	0	
+0.945	0.00293883	-0.00309058	-0.00309058	0	0	0	
+0.95	0.00291857	-0.00318553	-0.00318553	0	0	0	
+0.955	0.00289824	-0.00328016	-0.00328016	0	0	0	
+0.96	0.00287783	-0.00337446	-0.00337446	0	0	0	
+0.965	0.00285735	-0.00346842	-0.00346842	0	0	0	
+0.97	0.0028368	-0.00356204	-0.00356204	0	0	0	
+0.975	0.00281617	-0.0036553	-0.0036553	0	0	0	
+0.98	0.00279548	-0.00374819	-0.00374819	0	0	0	
+0.985	0.00277472	-0.00384071	-0.00384071	0	0	0	
+0.99	0.00275389	-0.00393285	-0.00393285	0	0	0	
+0.995	0.00273299	-0.00402459	-0.00402459	0	0	0	
+1	0.00271202	-0.00411593	-0.00411593	0	0	0	
+1.005	0.00269098	-0.00420686	-0.00420686	0	0	0	
+1.01	0.00266988	-0.00429737	-0.00429737	0	0	0	
+1.015	0.00264871	-0.00438745	-0.00438745	0	0	0	
+1.02	0.00262747	-0.00447709	-0.00447709	0	0	0	
+1.025	0.00260617	-0.00456628	-0.00456628	0	0	0	
+1.03	0.0025848	-0.00465502	-0.00465502	0	0	0	
+1.035	0.00256337	-0.00474329	-0.00474329	0	0	0	
+1.04	0.00254187	-0.00483108	-0.00483108	0	0	0	
+1.045	0.00252031	-0.0049184	-0.0049184	0	0	0	
+1.05	0.00249869	-0.00500522	-0.00500522	0	0	0	
+1.055	0.002477	-0.00509154	-0.00509154	0	0	0	
+1.06	0.00245525	-0.00517735	-0.00517735	0	0	0	
+1.065	0.00243345	-0.00526264	-0.00526264	0	0	0	
+1.07	0.00241158	-0.00534741	-0.00534741	0	0	0	
+1.075	0.00238965	-0.00543164	-0.00543164	0	0	0	
+1.08	0.00236766	-0.00551533	-0.00551533	0	0	0	
+1.085	0.00234561	-0.00559847	-0.00559847	0	0	0	
+1.09	0.0023235	-0.00568105	-0.00568105	0	0	0	
+1.095	0.00230133	-0.00576306	-0.00576306	0	0	0	
+1.1	0.00227911	-0.00584449	-0.00584449	0	0	0	
+1.105	0.00225683	-0.00592534	-0.00592534	0	0	0	
+1.11	0.00223449	-0.00600559	-0.00600559	0	0	0	
+1.115	0.0022121	-0.00608525	-0.00608525	0	0	0	
+1.12	0.00218965	-0.0061643	-0.0061643	0	0	0	
+1.125	0.00216715	-0.00624273	-0.00624273	0	0	0	
+1.13	0.0021446	-0.00632053	-0.00632053	0	0	0	
+1.135	0.00212199	-0.00639771	-0.00639771	0	0	0	
+1.14	0.00209932	-0.00647424	-0.00647424	0	0	0	
+1.145	0.00207661	-0.00655013	-0.00655013	0	0	0	
+1.15	0.00205384	-0.00662536	-0.00662536	0	0	0	
+1.155	0.00203102	-0.00669993	-0.00669993	0	0	0	
+1.16	0.00200815	-0.00677383	-0.00677383	0	0	0	
+1.165	0.00198523	-0.00684706	-0.00684706	0	0	0	
+1.17	0.00196226	-0.00691959	-0.00691959	0	0	0	
+1.175	0.00193924	-0.00699144	-0.00699144	0	0	0	
+1.18	0.00191617	-0.00706259	-0.00706259	0	0	0	
+1.185	0.00189306	-0.00713303	-0.00713303	0	0	0	
+1.19	0.0018699	-0.00720275	-0.00720275	0	0	0	
+1.195	0.00184669	-0.00727176	-0.00727176	0	0	0	
+1.2	0.00182343	-0.00734004	-0.00734004	0	0	0	
+1.205	0.00180013	-0.00740759	-0.00740759	0	0	0	
+1.21	0.00177678	-0.00747439	-0.00747439	0	0	0	
+1.215	0.00175339	-0.00754045	-0.00754045	0	0	0	
+1.22	0.00172996	-0.00760575	-0.00760575	0	0	0	
+1.225	0.00170648	-0.0076703	-0.0076703	0	0	0	
+1.23	0.00168296	-0.00773407	-0.00773407	0	0	0	
+1.235	0.0016594	-0.00779707	-0.00779707	0	0	0	
+1.24	0.0016358	-0.0078593	-0.0078593	0	0	0	
+1.245	0.00161215	-0.00792073	-0.00792073	0	0	0	
+1.25	0.00158847	-0.00798138	-0.00798138	0	0	0	
+1.255	0.00156474	-0.00804123	-0.00804123	0	0	0	
+1.26	0.00154098	-0.00810027	-0.00810027	0	0	0	
+1.265	0.00151718	-0.0081585	-0.0081585	0	0	0	
+1.27	0.00149334	-0.00821592	-0.00821592	0	0	0	
+1.275	0.00146946	-0.00827251	-0.00827251	0	0	0	
+1.28	0.00144555	-0.00832828	-0.00832828	0	0	0	
+1.285	0.00142159	-0.00838322	-0.00838322	0	0	0	
+1.29	0.00139761	-0.00843731	-0.00843731	0	0	0	
+1.295	0.00137359	-0.00849057	-0.00849057	0	0	0	
+1.3	0.00134953	-0.00854297	-0.00854297	0	0	0	
+1.305	0.00132544	-0.00859452	-0.00859452	0	0	0	
+1.31	0.00130132	-0.00864521	-0.00864521	0	0	0	
+1.315	0.00127717	-0.00869504	-0.00869504	0	0	0	
+1.32	0.00125298	-0.00874399	-0.00874399	0	0	0	
+1.325	0.00122876	-0.00879207	-0.00879207	0	0	0	
+1.33	0.00120451	-0.00883928	-0.00883928	0	0	0	
+1.335	0.00118024	-0.0088856	-0.0088856	0	0	0	
+1.34	0.00115593	-0.00893103	-0.00893103	0	0	0	
+1.345	0.00113159	-0.00897556	-0.00897556	0	0	0	
+1.35	0.00110723	-0.0090192	-0.0090192	0	0	0	
+1.355	0.00108283	-0.00906194	-0.00906194	0	0	0	
+1.36	0.00105841	-0.00910377	-0.00910377	0	0	0	
+1.365	0.00103397	-0.00914469	-0.00914469	0	0	0	
+1.37	0.00100949	-0.0091847	-0.0091847	0	0	0	
+1.375	0.000984996	-0.00922379	-0.00922379	0	0	0	
+1.38	0.000960473	-0.00926195	-0.00926195	0	0	0	
+1.385	0.000935927	-0.00929919	-0.00929919	0	0	0	
+1.39	0.000911357	-0.0093355	-0.0093355	0	0	0	
+1.395	0.000886765	-0.00937088	-0.00937088	0	0	0	
+1.4	0.00086215	-0.00940532	-0.00940532	0	0	0	
+1.405	0.000837514	-0.00943882	-0.00943882	0	0	0	
+1.41	0.000812857	-0.00947137	-0.00947137	0	0	0	
+1.415	0.000788179	-0.00950298	-0.00950298	0	0	0	
+1.42	0.000763482	-0.00953364	-0.00953364	0	0	0	
+1.425	0.000738766	-0.00956334	-0.00956334	0	0	0	
+1.43	0.000714031	-0.00959209	-0.00959209	0	0	0	
+1.435	0.000689279	-0.00961987	-0.00961987	0	0	0	
+1.44	0.000664509	-0.0096467	-0.0096467	0	0	0	
+1.445	0.000639723	-0.00967256	-0.00967256	0	0	0	
+1.45	0.00061492	-0.00969746	-0.00969746	0	0	0	
+1.455	0.000590102	-0.00972138	-0.00972138	0	0	0	
+1.46	0.00056527	-0.00974433	-0.00974433	0	0	0	
+1.465	0.000540423	-0.00976631	-0.00976631	0	0	0	
+1.47	0.000515563	-0.00978731	-0.00978731	0	0	0	
+1.475	0.00049069	-0.00980734	-0.00980734	0	0	0	
+1.48	0.000465805	-0.00982638	-0.00982638	0	0	0	
+1.485	0.000440908	-0.00984444	-0.00984444	0	0	0	
+1.49	0.000416	-0.00986151	-0.00986151	0	0	0	
+1.495	0.000391081	-0.0098776	-0.0098776	0	0	0	
+1.5	0.000366153	-0.0098927	-0.0098927	0	0	0	
+1.505	0.000341216	-0.00990682	-0.00990682	0	0	0	
+1.51	0.00031627	-0.00991994	-0.00991994	0	0	0	
+1.515	0.000291316	-0.00993207	-0.00993207	0	0	0	
+1.52	0.000266355	-0.0099432	-0.0099432	0	0	0	
+1.525	0.000241388	-0.00995334	-0.00995334	0	0	0	
+1.53	0.000216414	-0.00996249	-0.00996249	0	0	0	
+1.535	0.000191435	-0.00997064	-0.00997064	0	0	0	
+1.54	0.000166451	-0.00997779	-0.00997779	0	0	0	
+1.545	0.000141463	-0.00998395	-0.00998395	0	0	0	
+1.55	0.000116471	-0.00998911	-0.00998911	0	0	0	
+1.555	9.14764e-05	-0.00999326	-0.00999326	0	0	0	
+1.56	6.64796e-05	-0.00999642	-0.00999642	0	0	0	
+1.565	4.14811e-05	-0.00999858	-0.00999858	0	0	0	
+1.57	1.64816e-05	-0.00999974	-0.00999974	0	0	0	
+1.575	-8.51835e-06	-0.0099999	-0.0099999	0	0	0	
+1.58	-3.35181e-05	-0.00999906	-0.00999906	0	0	0	
+1.585	-5.8517e-05	-0.00999722	-0.00999722	0	0	0	
+1.59	-8.35144e-05	-0.00999438	-0.00999438	0	0	0	
+1.595	-0.00010851	-0.00999054	-0.00999054	0	0	0	
+1.6	-0.000133502	-0.0099857	-0.0099857	0	0	0	
+1.605	-0.000158492	-0.00997986	-0.00997986	0	0	0	
+1.61	-0.000183477	-0.00997303	-0.00997303	0	0	0	
+1.615	-0.000208458	-0.00996519	-0.00996519	0	0	0	
+1.62	-0.000233433	-0.00995637	-0.00995637	0	0	0	
+1.625	-0.000258403	-0.00994654	-0.00994654	0	0	0	
+1.63	-0.000283366	-0.00993572	-0.00993572	0	0	0	
+1.635	-0.000308322	-0.00992391	-0.00992391	0	0	0	
+1.64	-0.000333271	-0.0099111	-0.0099111	0	0	0	
+1.645	-0.000358211	-0.00989731	-0.00989731	0	0	0	
+1.65	-0.000383142	-0.00988252	-0.00988252	0	0	0	
+1.655	-0.000408064	-0.00986675	-0.00986675	0	0	0	
+1.66	-0.000432975	-0.00984998	-0.00984998	0	0	0	
+1.665	-0.000457876	-0.00983224	-0.00983224	0	0	0	
+1.67	-0.000482765	-0.00981351	-0.00981351	0	0	0	
+1.675	-0.000507642	-0.0097938	-0.0097938	0	0	0	
+1.68	-0.000532506	-0.00977311	-0.00977311	0	0	0	
+1.685	-0.000557357	-0.00975144	-0.00975144	0	0	0	
+1.69	-0.000582194	-0.0097288	-0.0097288	0	0	0	
+1.695	-0.000607017	-0.00970518	-0.00970518	0	0	0	
+1.7	-0.000631824	-0.0096806	-0.0096806	0	0	0	
+1.705	-0.000656616	-0.00965504	-0.00965504	0	0	0	
+1.71	-0.000681391	-0.00962852	-0.00962852	0	0	0	
+1.715	-0.000706149	-0.00960104	-0.00960104	0	0	0	
+1.72	-0.000730889	-0.0095726	-0.0095726	0	0	0	
+1.725	-0.000755612	-0.0095432	-0.0095432	0	0	0	
+1.73	-0.000780315	-0.00951285	-0.00951285	0	0	0	
+1.735	-0.000804999	-0.00948154	-0.00948154	0	0	0	
+1.74	-0.000829662	-0.00944929	-0.00944929	0	0	0	
+1.745	-0.000854305	-0.00941609	-0.00941609	0	0	0	
+1.75	-0.000878927	-0.00938195	-0.00938195	0	0	0	
+1.755	-0.000903526	-0.00934687	-0.00934687	0	0	0	
+1.76	-0.000928103	-0.00931086	-0.00931086	0	0	0	
+1.765	-0.000952657	-0.00927392	-0.00927392	0	0	0	
+1.77	-0.000977187	-0.00923604	-0.00923604	0	0	0	
+1.775	-0.00100169	-0.00919725	-0.00919725	0	0	0	
+1.78	-0.00102617	-0.00915753	-0.00915753	0	0	0	
+1.785	-0.00105063	-0.0091169	-0.0091169	0	0	0	
+1.79	-0.00107506	-0.00907536	-0.00907536	0	0	0	
+1.795	-0.00109946	-0.00903291	-0.00903291	0	0	0	
+1.8	-0.00112383	-0.00898956	-0.00898956	0	0	0	
+1.805	-0.00114818	-0.00894531	-0.00894531	0	0	0	
+1.81	-0.0011725	-0.00890016	-0.00890016	0	0	0	
+1.815	-0.00119678	-0.00885413	-0.00885413	0	0	0	
+1.82	-0.00122104	-0.0088072	-0.0088072	0	0	0	
+1.825	-0.00124527	-0.0087594	-0.0087594	0	0	0	
+1.83	-0.00126947	-0.00871072	-0.00871072	0	0	0	
+1.835	-0.00129363	-0.00866117	-0.00866117	0	0	0	
+1.84	-0.00131776	-0.00861076	-0.00861076	0	0	0	
+1.845	-0.00134186	-0.00855948	-0.00855948	0	0	0	
+1.85	-0.00136593	-0.00850735	-0.00850735	0	0	0	
+1.855	-0.00138996	-0.00845437	-0.00845437	0	0	0	
+1.86	-0.00141396	-0.00840054	-0.00840054	0	0	0	
+1.865	-0.00143792	-0.00834587	-0.00834587	0	0	0	
+1.87	-0.00146185	-0.00829037	-0.00829037	0	0	0	
+1.875	-0.00148574	-0.00823403	-0.00823403	0	0	0	
+1.88	-0.00150959	-0.00817688	-0.00817688	0	0	0	
+1.885	-0.0015334	-0.00811891	-0.00811891	0	0	0	
+1.89	-0.00155718	-0.00806012	-0.00806012	0	0	0	
+1.895	-0.00158091	-0.00800053	-0.00800053	0	0	0	
+1.9	-0.00160461	-0.00794014	-0.00794014	0	0	0	
+1.905	-0.00162827	-0.00787895	-0.00787895	0	0	0	
+1.91	-0.00165189	-0.00781698	-0.00781698	0	0	0	
+1.915	-0.00167546	-0.00775422	-0.00775422	0	0	0	
+1.92	-0.001699	-0.00769069	-0.00769069	0	0	0	
+1.925	-0.00172249	-0.0076264	-0.0076264	0	0	0	
+1.93	-0.00174593	-0.00756133	-0.00756133	0	0	0	
+1.935	-0.00176934	-0.00749551	-0.00749551	0	0	0	
+1.94	-0.0017927	-0.00742895	-0.00742895	0	0	0	
+1.945	-0.00181601	-0.00736164	-0.00736164	0	0	0	
+1.95	-0.00183928	-0.00729359	-0.00729359	0	0	0	
+1.955	-0.00186251	-0.00722481	-0.00722481	0	0	0	
+1.96	-0.00188569	-0.00715532	-0.00715532	0	0	0	
+1.965	-0.00190882	-0.0070851	-0.0070851	0	0	0	
+1.97	-0.0019319	-0.00701418	-0.00701418	0	0	0	
+1.975	-0.00195493	-0.00694255	-0.00694255	0	0	0	
+1.98	-0.00197792	-0.00687024	-0.00687024	0	0	0	
+1.985	-0.00200085	-0.00679723	-0.00679723	0	0	0	
+1.99	-0.00202374	-0.00672355	-0.00672355	0	0	0	
+1.995	-0.00204658	-0.00664919	-0.00664919	0	0	0	
+2	-0.00206936	-0.00657417	-0.00657417	0	0	0	
+2.005	-0.00209209	-0.00649849	-0.00649849	0	0	0	
+2.01	-0.00211477	-0.00642216	-0.00642216	0	0	0	
+2.015	-0.0021374	-0.00634519	-0.00634519	0	0	0	
+2.02	-0.00215997	-0.00626758	-0.00626758	0	0	0	
+2.025	-0.00218249	-0.00618935	-0.00618935	0	0	0	
+2.03	-0.00220496	-0.0061105	-0.0061105	0	0	0	
+2.035	-0.00222737	-0.00603103	-0.00603103	0	0	0	
+2.04	-0.00224972	-0.00595097	-0.00595097	0	0	0	
+2.045	-0.00227202	-0.00587031	-0.00587031	0	0	0	
+2.05	-0.00229426	-0.00578906	-0.00578906	0	0	0	
+2.055	-0.00231645	-0.00570723	-0.00570723	0	0	0	
+2.06	-0.00233857	-0.00562483	-0.00562483	0	0	0	
+2.065	-0.00236064	-0.00554187	-0.00554187	0	0	0	
+2.07	-0.00238265	-0.00545836	-0.00545836	0	0	0	
+2.075	-0.0024046	-0.0053743	-0.0053743	0	0	0	
+2.08	-0.00242649	-0.0052897	-0.0052897	0	0	0	
+2.085	-0.00244831	-0.00520457	-0.00520457	0	0	0	
+2.09	-0.00247008	-0.00511893	-0.00511893	0	0	0	
+2.095	-0.00249179	-0.00503277	-0.00503277	0	0	0	
+2.1	-0.00251343	-0.0049461	-0.0049461	0	0	0	
+2.105	-0.00253501	-0.00485895	-0.00485895	0	0	0	
+2.11	-0.00255653	-0.00477131	-0.00477131	0	0	0	
+2.115	-0.00257798	-0.00468319	-0.00468319	0	0	0	
+2.12	-0.00259937	-0.0045946	-0.0045946	0	0	0	
+2.125	-0.00262069	-0.00450555	-0.00450555	0	0	0	
+2.13	-0.00264195	-0.00441605	-0.00441605	0	0	0	
+2.135	-0.00266314	-0.00432611	-0.00432611	0	0	0	
+2.14	-0.00268427	-0.00423574	-0.00423574	0	0	0	
+2.145	-0.00270533	-0.00414494	-0.00414494	0	0	0	
+2.15	-0.00272632	-0.00405373	-0.00405373	0	0	0	
+2.155	-0.00274724	-0.00396212	-0.00396212	0	0	0	
+2.16	-0.00276809	-0.0038701	-0.0038701	0	0	0	
+2.165	-0.00278888	-0.00377771	-0.00377771	0	0	0	
+2.17	-0.00280959	-0.00368493	-0.00368493	0	0	0	
+2.175	-0.00283024	-0.00359178	-0.00359178	0	0	0	
+2.18	-0.00285081	-0.00349828	-0.00349828	0	0	0	
+2.185	-0.00287131	-0.00340443	-0.00340443	0	0	0	
+2.19	-0.00289174	-0.00331023	-0.00331023	0	0	0	
+2.195	-0.0029121	-0.0032157	-0.0032157	0	0	0	
+2.2	-0.00293239	-0.00312086	-0.00312086	0	0	0	
+2.205	-0.0029526	-0.0030257	-0.0030257	0	0	0	
+2.21	-0.00297274	-0.00293024	-0.00293024	0	0	0	
+2.215	-0.0029928	-0.00283448	-0.00283448	0	0	0	
+2.22	-0.00301279	-0.00273844	-0.00273844	0	0	0	
+2.225	-0.00303271	-0.00264213	-0.00264213	0	0	0	
+2.23	-0.00305254	-0.00254555	-0.00254555	0	0	0	
+2.235	-0.00307231	-0.00244872	-0.00244872	0	0	0	
+2.24	-0.00309199	-0.00235165	-0.00235165	0	0	0	
+2.245	-0.0031116	-0.00225434	-0.00225434	0	0	0	
+2.25	-0.00313113	-0.0021568	-0.0021568	0	0	0	
+2.255	-0.00315058	-0.00205905	-0.00205905	0	0	0	
+2.26	-0.00316995	-0.00196109	-0.00196109	0	0	0	
+2.265	-0.00318925	-0.00186293	-0.00186293	0	0	0	
+2.27	-0.00320846	-0.00176459	-0.00176459	0	0	0	
+2.275	-0.0032276	-0.00166608	-0.00166608	0	0	0	
+2.28	-0.00324665	-0.00156739	-0.00156739	0	0	0	
+2.285	-0.00326562	-0.00146855	-0.00146855	0	0	0	
+2.29	-0.00328451	-0.00136957	-0.00136957	0	0	0	
+2.295	-0.00330332	-0.00127044	-0.00127044	0	0	0	
+2.3	-0.00332204	-0.00117119	-0.00117119	0	0	0	
+2.305	-0.00334069	-0.00107182	-0.00107182	0	0	0	
+2.31	-0.00335925	-0.000972347	-0.000972347	0	0	0	
+2.315	-0.00337772	-0.000872774	-0.000872774	0	0	0	
+2.32	-0.00339611	-0.000773114	-0.000773114	0	0	0	
+2.325	-0.00341442	-0.000673377	-0.000673377	0	0	0	
+2.33	-0.00343264	-0.000573572	-0.000573572	0	0	0	
+2.335	-0.00345077	-0.00047371	-0.00047371	0	0	0	
+2.34	-0.00346882	-0.000373801	-0.000373801	0	0	0	
+2.345	-0.00348678	-0.000273854	-0.000273854	0	0	0	
+2.35	-0.00350466	-0.00017388	-0.00017388	0	0	0	
+2.355	-0.00352244	-7.38888e-05	-7.38888e-05	0	0	0	
+2.36	-0.00354014	2.61101e-05	2.61101e-05	0	0	0	
+2.365	-0.00355775	0.000126106	0.000126106	0	0	0	
+2.37	-0.00357527	0.00022609	0.00022609	0	0	0	
+2.375	-0.00359271	0.000326051	0.000326051	0	0	0	
+2.38	-0.00361005	0.000425979	0.000425979	0	0	0	
+2.385	-0.0036273	0.000525865	0.000525865	0	0	0	
+2.39	-0.00364446	0.000625699	0.000625699	0	0	0	
+2.395	-0.00366153	0.000725469	0.000725469	0	0	0	
+2.4	-0.00367851	0.000825167	0.000825167	0	0	0	
+2.405	-0.0036954	0.000924783	0.000924783	0	0	0	
+2.41	-0.00371219	0.00102431	0.00102431	0	0	0	
+2.415	-0.00372889	0.00112373	0.00112373	0	0	0	
+2.42	-0.0037455	0.00122304	0.00122304	0	0	0	
+2.425	-0.00376201	0.00132222	0.00132222	0	0	0	
+2.43	-0.00377844	0.00142128	0.00142128	0	0	0	
+2.435	-0.00379476	0.00152019	0.00152019	0	0	0	
+2.44	-0.00381099	0.00161895	0.00161895	0	0	0	
+2.445	-0.00382713	0.00171754	0.00171754	0	0	0	
+2.45	-0.00384317	0.00181597	0.00181597	0	0	0	
+2.455	-0.00385911	0.00191421	0.00191421	0	0	0	
+2.46	-0.00387496	0.00201227	0.00201227	0	0	0	
+2.465	-0.00389071	0.00211012	0.00211012	0	0	0	
+2.47	-0.00390636	0.00220776	0.00220776	0	0	0	
+2.475	-0.00392192	0.00230518	0.00230518	0	0	0	
+2.48	-0.00393738	0.00240237	0.00240237	0	0	0	
+2.485	-0.00395274	0.00249932	0.00249932	0	0	0	
+2.49	-0.003968	0.00259602	0.00259602	0	0	0	
+2.495	-0.00398316	0.00269246	0.00269246	0	0	0	
+2.5	-0.00399822	0.00278863	0.00278863	0	0	0	
+2.505	-0.00401318	0.00288452	0.00288452	0	0	0	
+2.51	-0.00402804	0.00298012	0.00298012	0	0	0	
+2.515	-0.0040428	0.00307543	0.00307543	0	0	0	
+2.52	-0.00405746	0.00317043	0.00317043	0	0	0	
+2.525	-0.00407202	0.00326511	0.00326511	0	0	0	
+2.53	-0.00408648	0.00335946	0.00335946	0	0	0	
+2.535	-0.00410083	0.00345348	0.00345348	0	0	0	
+2.54	-0.00411508	0.00354715	0.00354715	0	0	0	
+2.545	-0.00412923	0.00364047	0.00364047	0	0	0	
+2.55	-0.00414328	0.00373342	0.00373342	0	0	0	
+2.555	-0.00415722	0.003826	0.003826	0	0	0	
+2.56	-0.00417106	0.0039182	0.0039182	0	0	0	
+2.565	-0.00418479	0.00401001	0.00401001	0	0	0	
+2.57	-0.00419842	0.00410141	0.00410141	0	0	0	
+2.575	-0.00421195	0.00419241	0.00419241	0	0	0	
+2.58	-0.00422537	0.00428299	0.00428299	0	0	0	
+2.585	-0.00423868	0.00437313	0.00437313	0	0	0	
+2.59	-0.00425189	0.00446284	0.00446284	0	0	0	
+2.595	-0.00426499	0.00455211	0.00455211	0	0	0	
+2.6	-0.00427798	0.00464092	0.00464092	0	0	0	
+2.605	-0.00429087	0.00472926	0.00472926	0	0	0	
+2.61	-0.00430365	0.00481713	0.00481713	0	0	0	
+2.615	-0.00431632	0.00490452	0.00490452	0	0	0	
+2.62	-0.00432889	0.00499142	0.00499142	0	0	0	
+2.625	-0.00434134	0.00507782	0.00507782	0	0	0	
+2.63	-0.00435369	0.00516372	0.00516372	0	0	0	
+2.635	-0.00436593	0.00524909	0.00524909	0	0	0	
+2.64	-0.00437806	0.00533394	0.00533394	0	0	0	
+2.645	-0.00439008	0.00541826	0.00541826	0	0	0	
+2.65	-0.00440199	0.00550204	0.00550204	0	0	0	
+2.655	-0.00441379	0.00558526	0.00558526	0	0	0	
+2.66	-0.00442548	0.00566793	0.00566793	0	0	0	
+2.665	-0.00443706	0.00575003	0.00575003	0	0	0	
+2.67	-0.00444853	0.00583156	0.00583156	0	0	0	
+2.675	-0.00445989	0.0059125	0.0059125	0	0	0	
+2.68	-0.00447114	0.00599285	0.00599285	0	0	0	
+2.685	-0.00448227	0.0060726	0.0060726	0	0	0	
+2.69	-0.00449329	0.00615175	0.00615175	0	0	0	
+2.695	-0.0045042	0.00623028	0.00623028	0	0	0	
+2.7	-0.004515	0.00630819	0.00630819	0	0	0	
+2.705	-0.00452568	0.00638546	0.00638546	0	0	0	
+2.71	-0.00453626	0.0064621	0.0064621	0	0	0	
+2.715	-0.00454671	0.00653809	0.00653809	0	0	0	
+2.72	-0.00455706	0.00661343	0.00661343	0	0	0	
+2.725	-0.00456729	0.0066881	0.0066881	0	0	0	
+2.73	-0.0045774	0.00676211	0.00676211	0	0	0	
+2.735	-0.00458741	0.00683544	0.00683544	0	0	0	
+2.74	-0.00459729	0.00690809	0.00690809	0	0	0	
+2.745	-0.00460706	0.00698004	0.00698004	0	0	0	
+2.75	-0.00461672	0.0070513	0.0070513	0	0	0	
+2.755	-0.00462626	0.00712186	0.00712186	0	0	0	
+2.76	-0.00463569	0.0071917	0.0071917	0	0	0	
+2.765	-0.004645	0.00726082	0.00726082	0	0	0	
+2.77	-0.00465419	0.00732922	0.00732922	0	0	0	
+2.775	-0.00466327	0.00739688	0.00739688	0	0	0	
+2.78	-0.00467223	0.0074638	0.0074638	0	0	0	
+2.785	-0.00468108	0.00752998	0.00752998	0	0	0	
+2.79	-0.0046898	0.0075954	0.0075954	0	0	0	
+2.795	-0.00469841	0.00766007	0.00766007	0	0	0	
+2.8	-0.0047069	0.00772397	0.00772397	0	0	0	
+2.805	-0.00471528	0.00778709	0.00778709	0	0	0	
+2.81	-0.00472354	0.00784944	0.00784944	0	0	0	
+2.815	-0.00473167	0.007911	0.007911	0	0	0	
+2.82	-0.0047397	0.00797177	0.00797177	0	0	0	
+2.825	-0.0047476	0.00803175	0.00803175	0	0	0	
+2.83	-0.00475538	0.00809092	0.00809092	0	0	0	
+2.835	-0.00476304	0.00814928	0.00814928	0	0	0	
+2.84	-0.00477059	0.00820683	0.00820683	0	0	0	
+2.845	-0.00477802	0.00826355	0.00826355	0	0	0	
+2.85	-0.00478532	0.00831945	0.00831945	0	0	0	
+2.855	-0.00479251	0.00837452	0.00837452	0	0	0	
+2.86	-0.00479958	0.00842875	0.00842875	0	0	0	
+2.865	-0.00480652	0.00848214	0.00848214	0	0	0	
+2.87	-0.00481335	0.00853468	0.00853468	0	0	0	
+2.875	-0.00482006	0.00858637	0.00858637	0	0	0	
+2.88	-0.00482664	0.00863719	0.00863719	0	0	0	
+2.885	-0.00483311	0.00868716	0.00868716	0	0	0	
+2.89	-0.00483945	0.00873625	0.00873625	0	0	0	
+2.895	-0.00484568	0.00878447	0.00878447	0	0	0	
+2.9	-0.00485178	0.00883182	0.00883182	0	0	0	
+2.905	-0.00485776	0.00887828	0.00887828	0	0	0	
+2.91	-0.00486362	0.00892385	0.00892385	0	0	0	
+2.915	-0.00486936	0.00896853	0.00896853	0	0	0	
+2.92	-0.00487498	0.00901231	0.00901231	0	0	0	
+2.925	-0.00488047	0.00905519	0.00905519	0	0	0	
+2.93	-0.00488584	0.00909717	0.00909717	0	0	0	
+2.935	-0.00489109	0.00913824	0.00913824	0	0	0	
+2.94	-0.00489622	0.00917839	0.00917839	0	0	0	
+2.945	-0.00490123	0.00921762	0.00921762	0	0	0	
+2.95	-0.00490611	0.00925594	0.00925594	0	0	0	
+2.955	-0.00491087	0.00929332	0.00929332	0	0	0	
+2.96	-0.00491551	0.00932978	0.00932978	0	0	0	
+2.965	-0.00492002	0.00936531	0.00936531	0	0	0	
+2.97	-0.00492442	0.0093999	0.0093999	0	0	0	
+2.975	-0.00492868	0.00943354	0.00943354	0	0	0	
+2.98	-0.00493283	0.00946625	0.00946625	0	0	0	
+2.985	-0.00493685	0.00949801	0.00949801	0	0	0	
+2.99	-0.00494075	0.00952882	0.00952882	0	0	0	
+2.995	-0.00494453	0.00955867	0.00955867	0	0	0	
+3	-0.00494818	0.00958757	0.00958757	0	0	0	
+3.005	-0.00495171	0.00961551	0.00961551	0	0	0	
+3.01	-0.00495511	0.00964249	0.00964249	0	0	0	
+3.015	-0.00495839	0.00966851	0.00966851	0	0	0	
+3.02	-0.00496155	0.00969356	0.00969356	0	0	0	
+3.025	-0.00496458	0.00971764	0.00971764	0	0	0	
+3.03	-0.00496749	0.00974074	0.00974074	0	0	0	
+3.035	-0.00497027	0.00976288	0.00976288	0	0	0	
+3.04	-0.00497293	0.00978404	0.00978404	0	0	0	
+3.045	-0.00497547	0.00980421	0.00980421	0	0	0	
+3.05	-0.00497788	0.00982341	0.00982341	0	0	0	
+3.055	-0.00498016	0.00984163	0.00984163	0	0	0	
+3.06	-0.00498233	0.00985886	0.00985886	0	0	0	
+3.065	-0.00498436	0.00987511	0.00987511	0	0	0	
+3.07	-0.00498628	0.00989037	0.00989037	0	0	0	
+3.075	-0.00498807	0.00990463	0.00990463	0	0	0	
+3.08	-0.00498973	0.00991791	0.00991791	0	0	0	
+3.085	-0.00499127	0.0099302	0.0099302	0	0	0	
+3.09	-0.00499268	0.0099415	0.0099415	0	0	0	
+3.095	-0.00499397	0.0099518	0.0099518	0	0	0	
+3.1	-0.00499514	0.0099611	0.0099611	0	0	0	
+3.105	-0.00499617	0.00996941	0.00996941	0	0	0	
+3.11	-0.00499709	0.00997672	0.00997672	0	0	0	
+3.115	-0.00499788	0.00998304	0.00998304	0	0	0	
+3.12	-0.00499854	0.00998835	0.00998835	0	0	0	
+3.125	-0.00499908	0.00999267	0.00999267	0	0	0	
+3.13	-0.0049995	0.00999599	0.00999599	0	0	0	
+3.135	-0.00499979	0.0099983	0.0099983	0	0	0	
+3.14	-0.00499995	0.00999962	0.00999962	0	0	0	
+3.145	-0.00499999	0.00999994	0.00999994	0	0	0	
+3.15	-0.00499991	0.00999926	0.00999926	0	0	0	
+3.155	-0.0049997	0.00999758	0.00999758	0	0	0	
+3.16	-0.00499936	0.0099949	0.0099949	0	0	0	
+3.165	-0.0049989	0.00999122	0.00999122	0	0	0	
+3.17	-0.00499832	0.00998654	0.00998654	0	0	0	
+3.175	-0.00499761	0.00998086	0.00998086	0	0	0	
+3.18	-0.00499677	0.00997418	0.00997418	0	0	0	
+3.185	-0.00499581	0.00996651	0.00996651	0	0	0	
+3.19	-0.00499473	0.00995784	0.00995784	0	0	0	
+3.195	-0.00499352	0.00994817	0.00994817	0	0	0	
+3.2	-0.00499218	0.00993751	0.00993751	0	0	0	
+3.205	-0.00499072	0.00992586	0.00992586	0	0	0	
+3.21	-0.00498914	0.00991321	0.00991321	0	0	0	
+3.215	-0.00498743	0.00989957	0.00989957	0	0	0	
+3.22	-0.0049856	0.00988494	0.00988494	0	0	0	
+3.225	-0.00498364	0.00986932	0.00986932	0	0	0	
+3.23	-0.00498156	0.00985272	0.00985272	0	0	0	
+3.235	-0.00497935	0.00983513	0.00983513	0	0	0	
+3.24	-0.00497702	0.00981656	0.00981656	0	0	0	
+3.245	-0.00497456	0.009797	0.009797	0	0	0	
+3.25	-0.00497198	0.00977647	0.00977647	0	0	0	
+3.255	-0.00496928	0.00975496	0.00975496	0	0	0	
+3.26	-0.00496645	0.00973247	0.00973247	0	0	0	
+3.265	-0.00496349	0.00970901	0.00970901	0	0	0	
+3.27	-0.00496042	0.00968458	0.00968458	0	0	0	
+3.275	-0.00495721	0.00965918	0.00965918	0	0	0	
+3.28	-0.00495389	0.00963281	0.00963281	0	0	0	
+3.285	-0.00495044	0.00960548	0.00960548	0	0	0	
+3.29	-0.00494687	0.00957719	0.00957719	0	0	0	
+3.295	-0.00494317	0.00954795	0.00954795	0	0	0	
+3.3	-0.00493935	0.00951774	0.00951774	0	0	0	
+3.305	-0.00493541	0.00948659	0.00948659	0	0	0	
+3.31	-0.00493134	0.00945449	0.00945449	0	0	0	
+3.315	-0.00492715	0.00942144	0.00942144	0	0	0	
+3.32	-0.00492284	0.00938745	0.00938745	0	0	0	
+3.325	-0.0049184	0.00935252	0.00935252	0	0	0	
+3.33	-0.00491384	0.00931666	0.00931666	0	0	0	
+3.335	-0.00490916	0.00927986	0.00927986	0	0	0	
+3.34	-0.00490435	0.00924214	0.00924214	0	0	0	
+3.345	-0.00489942	0.00920349	0.00920349	0	0	0	
+3.35	-0.00489437	0.00916392	0.00916392	0	0	0	
+3.355	-0.0048892	0.00912344	0.00912344	0	0	0	
+3.36	-0.00488391	0.00908204	0.00908204	0	0	0	
+3.365	-0.00487849	0.00903973	0.00903973	0	0	0	
+3.37	-0.00487295	0.00899653	0.00899653	0	0	0	
+3.375	-0.00486729	0.00895242	0.00895242	0	0	0	
+3.38	-0.00486151	0.00890741	0.00890741	0	0	0	
+3.385	-0.0048556	0.00886152	0.00886152	0	0	0	
+3.39	-0.00484958	0.00881474	0.00881474	0	0	0	
+3.395	-0.00484343	0.00876707	0.00876707	0	0	0	
+3.4	-0.00483717	0.00871854	0.00871854	0	0	0	
+3.405	-0.00483078	0.00866912	0.00866912	0	0	0	
+3.41	-0.00482427	0.00861885	0.00861885	0	0	0	
+3.415	-0.00481764	0.00856771	0.00856771	0	0	0	
+3.42	-0.00481089	0.00851571	0.00851571	0	0	0	
+3.425	-0.00480402	0.00846286	0.00846286	0	0	0	
+3.43	-0.00479703	0.00840917	0.00840917	0	0	0	
+3.435	-0.00478992	0.00835463	0.00835463	0	0	0	
+3.44	-0.00478268	0.00829926	0.00829926	0	0	0	
+3.445	-0.00477533	0.00824306	0.00824306	0	0	0	
+3.45	-0.00476787	0.00818604	0.00818604	0	0	0	
+3.455	-0.00476028	0.00812819	0.00812819	0	0	0	
+3.46	-0.00475257	0.00806954	0.00806954	0	0	0	
+3.465	-0.00474474	0.00801007	0.00801007	0	0	0	
+3.47	-0.0047368	0.00794981	0.00794981	0	0	0	
+3.475	-0.00472873	0.00788875	0.00788875	0	0	0	
+3.48	-0.00472055	0.0078269	0.0078269	0	0	0	
+3.485	-0.00471225	0.00776427	0.00776427	0	0	0	
+3.49	-0.00470384	0.00770086	0.00770086	0	0	0	
+3.495	-0.0046953	0.00763669	0.00763669	0	0	0	
+3.5	-0.00468665	0.00757175	0.00757175	0	0	0	
+3.505	-0.00467788	0.00750605	0.00750605	0	0	0	
+3.51	-0.00466899	0.0074396	0.0074396	0	0	0	
+3.515	-0.00465999	0.00737241	0.00737241	0	0	0	
+3.52	-0.00465087	0.00730448	0.00730448	0	0	0	
+3.525	-0.00464163	0.00723582	0.00723582	0	0	0	
+3.53	-0.00463228	0.00716643	0.00716643	0	0	0	
+3.535	-0.00462281	0.00709633	0.00709633	0	0	0	
+3.54	-0.00461323	0.00702552	0.00702552	0	0	0	
+3.545	-0.00460353	0.00695401	0.00695401	0	0	0	
+3.55	-0.00459372	0.0068818	0.0068818	0	0	0	
+3.555	-0.00458379	0.0068089	0.0068089	0	0	0	
+3.56	-0.00457375	0.00673533	0.00673533	0	0	0	
+3.565	-0.00456359	0.00666108	0.00666108	0	0	0	
+3.57	-0.00455332	0.00658616	0.00658616	0	0	0	
+3.575	-0.00454293	0.00651058	0.00651058	0	0	0	
+3.58	-0.00453243	0.00643436	0.00643436	0	0	0	
+3.585	-0.00452182	0.00635749	0.00635749	0	0	0	
+3.59	-0.00451109	0.00627998	0.00627998	0	0	0	
+3.595	-0.00450026	0.00620185	0.00620185	0	0	0	
+3.6	-0.0044893	0.00612309	0.00612309	0	0	0	
+3.605	-0.00447824	0.00604373	0.00604373	0	0	0	
+3.61	-0.00446707	0.00596376	0.00596376	0	0	0	
+3.615	-0.00445578	0.00588319	0.00588319	0	0	0	
+3.62	-0.00444438	0.00580204	0.00580204	0	0	0	
+3.625	-0.00443287	0.0057203	0.0057203	0	0	0	
+3.63	-0.00442125	0.00563799	0.00563799	0	0	0	
+3.635	-0.00440952	0.00555512	0.00555512	0	0	0	
+3.64	-0.00439768	0.0054717	0.0054717	0	0	0	
+3.645	-0.00438573	0.00538772	0.00538772	0	0	0	
+3.65	-0.00437367	0.00530321	0.00530321	0	0	0	
+3.655	-0.0043615	0.00521817	0.00521817	0	0	0	
+3.66	-0.00434922	0.0051326	0.0051326	0	0	0	
+3.665	-0.00433684	0.00504652	0.00504652	0	0	0	
+3.67	-0.00432434	0.00495994	0.00495994	0	0	0	
+3.675	-0.00431174	0.00487286	0.00487286	0	0	0	
+3.68	-0.00429902	0.0047853	0.0047853	0	0	0	
+3.685	-0.0042862	0.00469725	0.00469725	0	0	0	
+3.69	-0.00427328	0.00460874	0.00460874	0	0	0	
+3.695	-0.00426025	0.00451976	0.00451976	0	0	0	
+3.7	-0.00424711	0.00443034	0.00443034	0	0	0	
+3.705	-0.00423386	0.00434047	0.00434047	0	0	0	
+3.71	-0.00422051	0.00425016	0.00425016	0	0	0	
+3.715	-0.00420705	0.00415943	0.00415943	0	0	0	
+3.72	-0.00419349	0.00406829	0.00406829	0	0	0	
+3.725	-0.00417982	0.00397673	0.00397673	0	0	0	
+3.73	-0.00416605	0.00388479	0.00388479	0	0	0	
+3.735	-0.00415217	0.00379245	0.00379245	0	0	0	
+3.74	-0.00413819	0.00369973	0.00369973	0	0	0	
+3.745	-0.00412411	0.00360664	0.00360664	0	0	0	
+3.75	-0.00410992	0.0035132	0.0035132	0	0	0	
+3.755	-0.00409564	0.0034194	0.0034194	0	0	0	
+3.76	-0.00408124	0.00332525	0.00332525	0	0	0	
+3.765	-0.00406675	0.00323078	0.00323078	0	0	0	
+3.77	-0.00405216	0.00313598	0.00313598	0	0	0	
+3.775	-0.00403746	0.00304087	0.00304087	0	0	0	
+3.78	-0.00402266	0.00294546	0.00294546	0	0	0	
+3.785	-0.00400776	0.00284975	0.00284975	0	0	0	
+3.79	-0.00399277	0.00275376	0.00275376	0	0	0	
+3.795	-0.00397767	0.00265749	0.00265749	0	0	0	
+3.8	-0.00396247	0.00256095	0.00256095	0	0	0	
+3.805	-0.00394717	0.00246416	0.00246416	0	0	0	
+3.81	-0.00393178	0.00236712	0.00236712	0	0	0	
+3.815	-0.00391629	0.00226985	0.00226985	0	0	0	
+3.82	-0.00390069	0.00217235	0.00217235	0	0	0	
+3.825	-0.00388501	0.00207463	0.00207463	0	0	0	
+3.83	-0.00386922	0.0019767	0.0019767	0	0	0	
+3.835	-0.00385334	0.00187858	0.00187858	0	0	0	
+3.84	-0.00383736	0.00178027	0.00178027	0	0	0	
+3.845	-0.00382128	0.00168178	0.00168178	0	0	0	
+3.85	-0.00380511	0.00158312	0.00158312	0	0	0	
+3.855	-0.00378885	0.00148431	0.00148431	0	0	0	
+3.86	-0.00377249	0.00138534	0.00138534	0	0	0	
+3.865	-0.00375603	0.00128624	0.00128624	0	0	0	
+3.87	-0.00373948	0.00118701	0.00118701	0	0	0	
+3.875	-0.00372284	0.00108766	0.00108766	0	0	0	
+3.88	-0.00370611	0.000988197	0.000988197	0	0	0	
+3.885	-0.00368928	0.000888639	0.000888639	0	0	0	
+3.89	-0.00367236	0.000788992	0.000788992	0	0	0	
+3.895	-0.00365535	0.000689267	0.000689267	0	0	0	
+3.9	-0.00363824	0.000589472	0.000589472	0	0	0	
+3.905	-0.00362105	0.000489618	0.000489618	0	0	0	
+3.91	-0.00360376	0.000389716	0.000389716	0	0	0	
+3.915	-0.00358639	0.000289775	0.000289775	0	0	0	
+3.92	-0.00356893	0.000189804	0.000189804	0	0	0	
+3.925	-0.00355137	8.98148e-05	8.98148e-05	0	0	0	
+3.93	-0.00353373	-1.01836e-05	-1.01836e-05	0	0	0	
+3.935	-0.003516	-0.000110181	-0.000110181	0	0	0	
+3.94	-0.00349818	-0.000210167	-0.000210167	0	0	0	
+3.945	-0.00348027	-0.000310133	-0.000310133	0	0	0	
+3.95	-0.00346228	-0.000410067	-0.000410067	0	0	0	
+3.955	-0.0034442	-0.00050996	-0.00050996	0	0	0	
+3.96	-0.00342604	-0.000609803	-0.000609803	0	0	0	
+3.965	-0.00340778	-0.000709584	-0.000709584	0	0	0	
+3.97	-0.00338945	-0.000809294	-0.000809294	0	0	0	
+3.975	-0.00337103	-0.000908924	-0.000908924	0	0	0	
+3.98	-0.00335252	-0.00100846	-0.00100846	0	0	0	
+3.985	-0.00333393	-0.0011079	-0.0011079	0	0	0	
+3.99	-0.00331526	-0.00120723	-0.00120723	0	0	0	
+3.995	-0.0032965	-0.00130643	-0.00130643	0	0	0	
+4	-0.00327766	-0.00140551	-0.00140551	0	0	0	
+4.005	-0.00325874	-0.00150444	-0.00150444	0	0	0	
+4.01	-0.00323974	-0.00160323	-0.00160323	0	0	0	
+4.015	-0.00322066	-0.00170185	-0.00170185	0	0	0	
+4.02	-0.0032015	-0.00180031	-0.00180031	0	0	0	
+4.025	-0.00318225	-0.00189858	-0.00189858	0	0	0	
+4.03	-0.00316293	-0.00199666	-0.00199666	0	0	0	
+4.035	-0.00314353	-0.00209455	-0.00209455	0	0	0	
+4.04	-0.00312405	-0.00219222	-0.00219222	0	0	0	
+4.045	-0.00310449	-0.00228968	-0.00228968	0	0	0	
+4.05	-0.00308486	-0.00238691	-0.00238691	0	0	0	
+4.055	-0.00306514	-0.0024839	-0.0024839	0	0	0	
+4.06	-0.00304535	-0.00258063	-0.00258063	0	0	0	
+4.065	-0.00302549	-0.00267712	-0.00267712	0	0	0	
+4.07	-0.00300555	-0.00277333	-0.00277333	0	0	0	
+4.075	-0.00298553	-0.00286927	-0.00286927	0	0	0	
+4.08	-0.00296544	-0.00296492	-0.00296492	0	0	0	
+4.085	-0.00294527	-0.00306027	-0.00306027	0	0	0	
+4.09	-0.00292503	-0.00315532	-0.00315532	0	0	0	
+4.095	-0.00290472	-0.00325005	-0.00325005	0	0	0	
+4.1	-0.00288434	-0.00334446	-0.00334446	0	0	0	
+4.105	-0.00286388	-0.00343853	-0.00343853	0	0	0	
+4.11	-0.00284335	-0.00353226	-0.00353226	0	0	0	
+4.115	-0.00282275	-0.00362563	-0.00362563	0	0	0	
+4.12	-0.00280208	-0.00371864	-0.00371864	0	0	0	
+4.125	-0.00278134	-0.00381129	-0.00381129	0	0	0	
+4.13	-0.00276053	-0.00390354	-0.00390354	0	0	0	
+4.135	-0.00273965	-0.00399541	-0.00399541	0	0	0	
+4.14	-0.00271871	-0.00408688	-0.00408688	0	0	0	
+4.145	-0.00269769	-0.00417795	-0.00417795	0	0	0	
+4.15	-0.00267661	-0.00426859	-0.00426859	0	0	0	
+4.155	-0.00265546	-0.0043588	-0.0043588	0	0	0	
+4.16	-0.00263424	-0.00444859	-0.00444859	0	0	0	
+4.165	-0.00261296	-0.00453792	-0.00453792	0	0	0	
+4.17	-0.00259161	-0.0046268	-0.0046268	0	0	0	
+4.175	-0.0025702	-0.00471522	-0.00471522	0	0	0	
+4.18	-0.00254872	-0.00480317	-0.00480317	0	0	0	
+4.185	-0.00252719	-0.00489064	-0.00489064	0	0	0	
+4.19	-0.00250558	-0.00497762	-0.00497762	0	0	0	
+4.195	-0.00248392	-0.0050641	-0.0050641	0	0	0	
+4.2	-0.00246219	-0.00515007	-0.00515007	0	0	0	
+4.205	-0.0024404	-0.00523553	-0.00523553	0	0	0	
+4.21	-0.00241855	-0.00532047	-0.00532047	0	0	0	
+4.215	-0.00239664	-0.00540487	-0.00540487	0	0	0	
+4.22	-0.00237467	-0.00548873	-0.00548873	0	0	0	
+4.225	-0.00235264	-0.00557205	-0.00557205	0	0	0	
+4.23	-0.00233055	-0.0056548	-0.0056548	0	0	0	
+4.235	-0.0023084	-0.00573699	-0.00573699	0	0	0	
+4.24	-0.0022862	-0.00581861	-0.00581861	0	0	0	
+4.245	-0.00226393	-0.00589965	-0.00589965	0	0	0	
+4.25	-0.00224162	-0.00598009	-0.00598009	0	0	0	
+4.255	-0.00221924	-0.00605994	-0.00605994	0	0	0	
+4.26	-0.00219681	-0.00613918	-0.00613918	0	0	0	
+4.265	-0.00217433	-0.00621781	-0.00621781	0	0	0	
+4.27	-0.00215179	-0.00629582	-0.00629582	0	0	0	
+4.275	-0.00212919	-0.0063732	-0.0063732	0	0	0	
+4.28	-0.00210655	-0.00644994	-0.00644994	0	0	0	
+4.285	-0.00208385	-0.00652603	-0.00652603	0	0	0	
+4.29	-0.0020611	-0.00660147	-0.00660147	0	0	0	
+4.295	-0.00203829	-0.00667625	-0.00667625	0	0	0	
+4.3	-0.00201544	-0.00675037	-0.00675037	0	0	0	
+4.305	-0.00199254	-0.00682381	-0.00682381	0	0	0	
+4.31	-0.00196958	-0.00689656	-0.00689656	0	0	0	
+4.315	-0.00194658	-0.00696863	-0.00696863	0	0	0	
+4.32	-0.00192353	-0.00704	-0.00704	0	0	0	
+4.325	-0.00190043	-0.00711067	-0.00711067	0	0	0	
+4.33	-0.00187728	-0.00718062	-0.00718062	0	0	0	
+4.335	-0.00185408	-0.00724986	-0.00724986	0	0	0	
+4.34	-0.00183084	-0.00731837	-0.00731837	0	0	0	
+4.345	-0.00180756	-0.00738615	-0.00738615	0	0	0	
+4.35	-0.00178423	-0.00745319	-0.00745319	0	0	0	
+4.355	-0.00176085	-0.00751949	-0.00751949	0	0	0	
+4.36	-0.00173743	-0.00758503	-0.00758503	0	0	0	
+4.365	-0.00171397	-0.00764982	-0.00764982	0	0	0	
+4.37	-0.00169046	-0.00771384	-0.00771384	0	0	0	
+4.375	-0.00166691	-0.00777709	-0.00777709	0	0	0	
+4.38	-0.00164332	-0.00783956	-0.00783956	0	0	0	
+4.385	-0.00161969	-0.00790125	-0.00790125	0	0	0	
+4.39	-0.00159602	-0.00796215	-0.00796215	0	0	0	
+4.395	-0.0015723	-0.00802225	-0.00802225	0	0	0	
+4.4	-0.00154855	-0.00808155	-0.00808155	0	0	0	
+4.405	-0.00152476	-0.00814004	-0.00814004	0	0	0	
+4.41	-0.00150093	-0.00819772	-0.00819772	0	0	0	
+4.415	-0.00147707	-0.00825458	-0.00825458	0	0	0	
+4.42	-0.00145317	-0.00831061	-0.00831061	0	0	0	
+4.425	-0.00142923	-0.00836581	-0.00836581	0	0	0	
+4.43	-0.00140525	-0.00842017	-0.00842017	0	0	0	
+4.435	-0.00138124	-0.0084737	-0.0084737	0	0	0	
+4.44	-0.0013572	-0.00852637	-0.00852637	0	0	0	
+4.445	-0.00133312	-0.00857819	-0.00857819	0	0	0	
+4.45	-0.00130901	-0.00862916	-0.00862916	0	0	0	
+4.455	-0.00128486	-0.00867926	-0.00867926	0	0	0	
+4.46	-0.00126069	-0.00872849	-0.00872849	0	0	0	
+4.465	-0.00123648	-0.00877685	-0.00877685	0	0	0	
+4.47	-0.00121224	-0.00882434	-0.00882434	0	0	0	
+4.475	-0.00118797	-0.00887094	-0.00887094	0	0	0	
+4.48	-0.00116367	-0.00891665	-0.00891665	0	0	0	
+4.485	-0.00113935	-0.00896147	-0.00896147	0	0	0	
+4.49	-0.00111499	-0.0090054	-0.0090054	0	0	0	
+4.495	-0.00109061	-0.00904842	-0.00904842	0	0	0	
+4.5	-0.00106619	-0.00909055	-0.00909055	0	0	0	
+4.505	-0.00104176	-0.00913176	-0.00913176	0	0	0	
+4.51	-0.00101729	-0.00917205	-0.00917205	0	0	0	
+4.515	-0.000992802	-0.00921144	-0.00921144	0	0	0	
+4.52	-0.000968287	-0.0092499	-0.0092499	0	0	0	
+4.525	-0.000943748	-0.00928743	-0.00928743	0	0	0	
+4.53	-0.000919186	-0.00932404	-0.00932404	0	0	0	
+4.535	-0.000894601	-0.00935971	-0.00935971	0	0	0	
+4.54	-0.000869993	-0.00939445	-0.00939445	0	0	0	
+4.545	-0.000845364	-0.00942825	-0.00942825	0	0	0	
+4.55	-0.000820713	-0.0094611	-0.0094611	0	0	0	
+4.555	-0.000796042	-0.00949301	-0.00949301	0	0	0	
+4.56	-0.000771351	-0.00952397	-0.00952397	0	0	0	
+4.565	-0.000746641	-0.00955398	-0.00955398	0	0	0	
+4.57	-0.000721912	-0.00958303	-0.00958303	0	0	0	
+4.575	-0.000697165	-0.00961113	-0.00961113	0	0	0	
+4.58	-0.000672401	-0.00963826	-0.00963826	0	0	0	
+4.585	-0.00064762	-0.00966443	-0.00966443	0	0	0	
+4.59	-0.000622822	-0.00968963	-0.00968963	0	0	0	
+4.595	-0.000598009	-0.00971387	-0.00971387	0	0	0	
+4.6	-0.000573181	-0.00973713	-0.00973713	0	0	0	
+4.605	-0.000548339	-0.00975942	-0.00975942	0	0	0	
+4.61	-0.000523483	-0.00978073	-0.00978073	0	0	0	
+4.615	-0.000498614	-0.00980107	-0.00980107	0	0	0	
+4.62	-0.000473733	-0.00982042	-0.00982042	0	0	0	
+4.625	-0.000448839	-0.00983879	-0.00983879	0	0	0	
+4.63	-0.000423935	-0.00985618	-0.00985618	0	0	0	
+4.635	-0.00039902	-0.00987259	-0.00987259	0	0	0	
+4.64	-0.000374095	-0.009888	-0.009888	0	0	0	
+4.645	-0.00034916	-0.00990243	-0.00990243	0	0	0	
+4.65	-0.000324217	-0.00991587	-0.00991587	0	0	0	
+4.655	-0.000299266	-0.00992831	-0.00992831	0	0	0	
+4.66	-0.000274307	-0.00993976	-0.00993976	0	0	0	
+4.665	-0.000249341	-0.00995022	-0.00995022	0	0	0	
+4.67	-0.000224369	-0.00995969	-0.00995969	0	0	0	
+4.675	-0.000199392	-0.00996815	-0.00996815	0	0	0	
+4.68	-0.000174409	-0.00997562	-0.00997562	0	0	0	
+4.685	-0.000149422	-0.0099821	-0.0099821	0	0	0	
+4.69	-0.000124432	-0.00998757	-0.00998757	0	0	0	
+4.695	-9.94382e-05	-0.00999205	-0.00999205	0	0	0	
+4.7	-7.44421e-05	-0.00999553	-0.00999553	0	0	0	
+4.705	-4.9444e-05	-0.009998	-0.009998	0	0	0	
+4.71	-2.44448e-05	-0.00999948	-0.00999948	0	0	0	
+4.715	5.55097e-07	-0.00999996	-0.00999996	0	0	0	
+4.72	2.5555e-05	-0.00999944	-0.00999944	0	0	0	
+4.725	5.05542e-05	-0.00999791	-0.00999791	0	0	0	
+4.73	7.55521e-05	-0.00999539	-0.00999539	0	0	0	
+4.735	0.000100548	-0.00999187	-0.00999187	0	0	0	
+4.74	0.000125542	-0.00998735	-0.00998735	0	0	0	
+4.745	0.000150532	-0.00998183	-0.00998183	0	0	0	
+4.75	0.000175519	-0.00997531	-0.00997531	0	0	0	
+4.755	0.000200501	-0.0099678	-0.0099678	0	0	0	
+4.76	0.000225478	-0.00995929	-0.00995929	0	0	0	
+4.765	0.00025045	-0.00994978	-0.00994978	0	0	0	
+4.77	0.000275415	-0.00993928	-0.00993928	0	0	0	
+4.775	0.000300374	-0.00992778	-0.00992778	0	0	0	
+4.78	0.000325325	-0.00991529	-0.00991529	0	0	0	
+4.785	0.000350268	-0.00990181	-0.00990181	0	0	0	
+4.79	0.000375202	-0.00988734	-0.00988734	0	0	0	
+4.795	0.000400126	-0.00987188	-0.00987188	0	0	0	
+4.8	0.000425041	-0.00985543	-0.00985543	0	0	0	
+4.805	0.000449945	-0.009838	-0.009838	0	0	0	
+4.81	0.000474838	-0.00981958	-0.00981958	0	0	0	
+4.815	0.000499719	-0.00980018	-0.00980018	0	0	0	
+4.82	0.000524587	-0.00977981	-0.00977981	0	0	0	
+4.825	0.000549443	-0.00975845	-0.00975845	0	0	0	
+4.83	0.000574284	-0.00973612	-0.00973612	0	0	0	
+4.835	0.000599112	-0.00971281	-0.00971281	0	0	0	
+4.84	0.000623924	-0.00968853	-0.00968853	0	0	0	
+4.845	0.00064872	-0.00966329	-0.00966329	0	0	0	
+4.85	0.000673501	-0.00963708	-0.00963708	0	0	0	
+4.855	0.000698265	-0.0096099	-0.0096099	0	0	0	
+4.86	0.000723011	-0.00958176	-0.00958176	0	0	0	
+4.865	0.000747739	-0.00955267	-0.00955267	0	0	0	
+4.87	0.000772448	-0.00952262	-0.00952262	0	0	0	
+4.875	0.000797138	-0.00949162	-0.00949162	0	0	0	
+4.88	0.000821808	-0.00945966	-0.00945966	0	0	0	
+4.885	0.000846458	-0.00942677	-0.00942677	0	0	0	
+4.89	0.000871086	-0.00939293	-0.00939293	0	0	0	
+4.895	0.000895693	-0.00935815	-0.00935815	0	0	0	
+4.9	0.000920277	-0.00932243	-0.00932243	0	0	0	
+4.905	0.000944839	-0.00928578	-0.00928578	0	0	0	
+4.91	0.000969376	-0.00924821	-0.00924821	0	0	0	
+4.915	0.00099389	-0.00920971	-0.00920971	0	0	0	
+4.92	0.00101838	-0.00917028	-0.00917028	0	0	0	
+4.925	0.00104284	-0.00912995	-0.00912995	0	0	0	
+4.93	0.00106728	-0.00908869	-0.00908869	0	0	0	
+4.935	0.00109169	-0.00904653	-0.00904653	0	0	0	
+4.94	0.00111607	-0.00900347	-0.00900347	0	0	0	
+4.945	0.00114043	-0.0089595	-0.0089595	0	0	0	
+4.95	0.00116475	-0.00891464	-0.00891464	0	0	0	
+4.955	0.00118905	-0.00886889	-0.00886889	0	0	0	
+4.96	0.00121332	-0.00882225	-0.00882225	0	0	0	
+4.965	0.00123756	-0.00877472	-0.00877472	0	0	0	
+4.97	0.00126176	-0.00872632	-0.00872632	0	0	0	
+4.975	0.00128594	-0.00867705	-0.00867705	0	0	0	
+4.98	0.00131008	-0.00862691	-0.00862691	0	0	0	
+4.985	0.00133419	-0.00857591	-0.00857591	0	0	0	
+4.99	0.00135827	-0.00852405	-0.00852405	0	0	0	
+4.995	0.00138231	-0.00847134	-0.00847134	0	0	0	
+5	0.00140632	-0.00841778	-0.00841778	0	0	0	
+5.005	0.00143029	-0.00836337	-0.00836337	0	0	0	
+5.01	0.00145423	-0.00830814	-0.00830814	0	0	0	
+5.015	0.00147813	-0.00825207	-0.00825207	0	0	0	
+5.02	0.00150199	-0.00819517	-0.00819517	0	0	0	
+5.025	0.00152582	-0.00813746	-0.00813746	0	0	0	
+5.03	0.00154961	-0.00807893	-0.00807893	0	0	0	
+5.035	0.00157336	-0.0080196	-0.0080196	0	0	0	
+5.04	0.00159707	-0.00795946	-0.00795946	0	0	0	
+5.045	0.00162074	-0.00789853	-0.00789853	0	0	0	
+5.05	0.00164437	-0.0078368	-0.0078368	0	0	0	
+5.055	0.00166796	-0.0077743	-0.0077743	0	0	0	
+5.06	0.0016915	-0.00771101	-0.00771101	0	0	0	
+5.065	0.00171501	-0.00764696	-0.00764696	0	0	0	
+5.07	0.00173847	-0.00758214	-0.00758214	0	0	0	
+5.075	0.00176189	-0.00751656	-0.00751656	0	0	0	
+5.08	0.00178526	-0.00745023	-0.00745023	0	0	0	
+5.085	0.00180859	-0.00738316	-0.00738316	0	0	0	
+5.09	0.00183188	-0.00731534	-0.00731534	0	0	0	
+5.095	0.00185512	-0.0072468	-0.0072468	0	0	0	
+5.1	0.00187831	-0.00717753	-0.00717753	0	0	0	
+5.105	0.00190145	-0.00710754	-0.00710754	0	0	0	
+5.11	0.00192455	-0.00703685	-0.00703685	0	0	0	
+5.115	0.0019476	-0.00696545	-0.00696545	0	0	0	
+5.12	0.0019706	-0.00689335	-0.00689335	0	0	0	
+5.125	0.00199355	-0.00682056	-0.00682056	0	0	0	
+5.13	0.00201646	-0.00674709	-0.00674709	0	0	0	
+5.135	0.00203931	-0.00667295	-0.00667295	0	0	0	
+5.14	0.00206211	-0.00659814	-0.00659814	0	0	0	
+5.145	0.00208486	-0.00652266	-0.00652266	0	0	0	
+5.15	0.00210755	-0.00644654	-0.00644654	0	0	0	
+5.155	0.0021302	-0.00636977	-0.00636977	0	0	0	
+5.16	0.00215279	-0.00629237	-0.00629237	0	0	0	
+5.165	0.00217533	-0.00621433	-0.00621433	0	0	0	
+5.17	0.00219781	-0.00613568	-0.00613568	0	0	0	
+5.175	0.00222024	-0.00605641	-0.00605641	0	0	0	
+5.18	0.00224261	-0.00597653	-0.00597653	0	0	0	
+5.185	0.00226492	-0.00589606	-0.00589606	0	0	0	
+5.19	0.00228718	-0.005815	-0.005815	0	0	0	
+5.195	0.00230939	-0.00573336	-0.00573336	0	0	0	
+5.2	0.00233153	-0.00565114	-0.00565114	0	0	0	
+5.205	0.00235362	-0.00556836	-0.00556836	0	0	0	
+5.21	0.00237564	-0.00548502	-0.00548502	0	0	0	
+5.215	0.00239761	-0.00540113	-0.00540113	0	0	0	
+5.22	0.00241952	-0.0053167	-0.0053167	0	0	0	
+5.225	0.00244137	-0.00523175	-0.00523175	0	0	0	
+5.23	0.00246315	-0.00514626	-0.00514626	0	0	0	
+5.235	0.00248488	-0.00506027	-0.00506027	0	0	0	
+5.24	0.00250654	-0.00497376	-0.00497376	0	0	0	
+5.245	0.00252814	-0.00488676	-0.00488676	0	0	0	
+5.25	0.00254968	-0.00479927	-0.00479927	0	0	0	
+5.255	0.00257115	-0.00471131	-0.00471131	0	0	0	
+5.26	0.00259256	-0.00462287	-0.00462287	0	0	0	
+5.265	0.00261391	-0.00453396	-0.00453396	0	0	0	
+5.27	0.00263519	-0.00444461	-0.00444461	0	0	0	
+5.275	0.0026564	-0.00435481	-0.00435481	0	0	0	
+5.28	0.00267755	-0.00426457	-0.00426457	0	0	0	
+5.285	0.00269862	-0.00417391	-0.00417391	0	0	0	
+5.29	0.00271964	-0.00408283	-0.00408283	0	0	0	
+5.295	0.00274058	-0.00399134	-0.00399134	0	0	0	
+5.3	0.00276146	-0.00389946	-0.00389946	0	0	0	
+5.305	0.00278226	-0.00380718	-0.00380718	0	0	0	
+5.31	0.002803	-0.00371452	-0.00371452	0	0	0	
+5.315	0.00282367	-0.00362149	-0.00362149	0	0	0	
+5.32	0.00284426	-0.0035281	-0.0035281	0	0	0	
+5.325	0.00286479	-0.00343436	-0.00343436	0	0	0	
+5.33	0.00288524	-0.00334027	-0.00334027	0	0	0	
+5.335	0.00290562	-0.00324585	-0.00324585	0	0	0	
+5.34	0.00292593	-0.0031511	-0.0031511	0	0	0	
+5.345	0.00294617	-0.00305604	-0.00305604	0	0	0	
+5.35	0.00296633	-0.00296068	-0.00296068	0	0	0	
+5.355	0.00298642	-0.00286501	-0.00286501	0	0	0	
+5.36	0.00300643	-0.00276906	-0.00276906	0	0	0	
+5.365	0.00302637	-0.00267284	-0.00267284	0	0	0	
+5.37	0.00304623	-0.00257634	-0.00257634	0	0	0	
+5.375	0.00306602	-0.00247959	-0.00247959	0	0	0	
+5.38	0.00308573	-0.00238259	-0.00238259	0	0	0	
+5.385	0.00310536	-0.00228536	-0.00228536	0	0	0	
+5.39	0.00312492	-0.00218789	-0.00218789	0	0	0	
+5.395	0.00314439	-0.00209021	-0.00209021	0	0	0	
+5.4	0.00316379	-0.00199231	-0.00199231	0	0	0	
+5.405	0.00318311	-0.00189422	-0.00189422	0	0	0	
+5.41	0.00320235	-0.00179594	-0.00179594	0	0	0	
+5.415	0.00322151	-0.00169748	-0.00169748	0	0	0	
+5.42	0.00324059	-0.00159884	-0.00159884	0	0	0	
+5.425	0.00325959	-0.00150005	-0.00150005	0	0	0	
+5.43	0.0032785	-0.00140111	-0.00140111	0	0	0	
+5.435	0.00329734	-0.00130203	-0.00130203	0	0	0	
+5.44	0.00331609	-0.00120282	-0.00120282	0	0	0	
+5.445	0.00333476	-0.00110349	-0.00110349	0	0	0	
+5.45	0.00335334	-0.00100404	-0.00100404	0	0	0	
+5.455	0.00337185	-0.000904501	-0.000904501	0	0	0	
+5.46	0.00339026	-0.000804868	-0.000804868	0	0	0	
+5.465	0.0034086	-0.000705154	-0.000705154	0	0	0	
+5.47	0.00342684	-0.00060537	-0.00060537	0	0	0	
+5.475	0.00344501	-0.000505525	-0.000505525	0	0	0	
+5.48	0.00346308	-0.00040563	-0.00040563	0	0	0	
+5.485	0.00348107	-0.000305694	-0.000305694	0	0	0	
+5.49	0.00349897	-0.000205728	-0.000205728	0	0	0	
+5.495	0.00351679	-0.00010574	-0.00010574	0	0	0	
+5.5	0.00353451	-5.74285e-06	-5.74285e-06	0	0	0	
+5.505	0.00355215	9.42553e-05	9.42553e-05	0	0	0	
+5.51	0.0035697	0.000194244	0.000194244	0	0	0	
+5.515	0.00358716	0.000294213	0.000294213	0	0	0	
+5.52	0.00360453	0.000394153	0.000394153	0	0	0	
+5.525	0.00362181	0.000494054	0.000494054	0	0	0	
+5.53	0.003639	0.000593905	0.000593905	0	0	0	
+5.535	0.0036561	0.000693697	0.000693697	0	0	0	
+5.54	0.00367311	0.000793419	0.000793419	0	0	0	
+5.545	0.00369003	0.000893062	0.000893062	0	0	0	
+5.55	0.00370685	0.000992616	0.000992616	0	0	0	
+5.555	0.00372358	0.00109207	0.00109207	0	0	0	
+5.56	0.00374022	0.00119142	0.00119142	0	0	0	
+5.565	0.00375676	0.00129064	0.00129064	0	0	0	
+5.57	0.00377321	0.00138974	0.00138974	0	0	0	
+5.575	0.00378957	0.0014887	0.0014887	0	0	0	
+5.58	0.00380583	0.00158751	0.00158751	0	0	0	
+5.585	0.003822	0.00168616	0.00168616	0	0	0	
+5.59	0.00383807	0.00178464	0.00178464	0	0	0	
+5.595	0.00385404	0.00188294	0.00188294	0	0	0	
+5.6	0.00386992	0.00198106	0.00198106	0	0	0	
+5.605	0.0038857	0.00207897	0.00207897	0	0	0	
+5.61	0.00390139	0.00217668	0.00217668	0	0	0	
+5.615	0.00391698	0.00227417	0.00227417	0	0	0	
+5.62	0.00393246	0.00237144	0.00237144	0	0	0	
+5.625	0.00394786	0.00246846	0.00246846	0	0	0	
+5.63	0.00396315	0.00256524	0.00256524	0	0	0	
+5.635	0.00397834	0.00266177	0.00266177	0	0	0	
+5.64	0.00399343	0.00275803	0.00275803	0	0	0	
+5.645	0.00400843	0.00285401	0.00285401	0	0	0	
+5.65	0.00402332	0.0029497	0.0029497	0	0	0	
+5.655	0.00403811	0.0030451	0.0030451	0	0	0	
+5.66	0.00405281	0.0031402	0.0031402	0	0	0	
+5.665	0.0040674	0.00323498	0.00323498	0	0	0	
+5.67	0.00408189	0.00332944	0.00332944	0	0	0	
+5.675	0.00409627	0.00342357	0.00342357	0	0	0	
+5.68	0.00411056	0.00351735	0.00351735	0	0	0	
+5.685	0.00412474	0.00361078	0.00361078	0	0	0	
+5.69	0.00413882	0.00370386	0.00370386	0	0	0	
+5.695	0.00415279	0.00379656	0.00379656	0	0	0	
+5.7	0.00416666	0.00388888	0.00388888	0	0	0	
+5.705	0.00418043	0.00398081	0.00398081	0	0	0	
+5.71	0.00419409	0.00407234	0.00407234	0	0	0	
+5.715	0.00420765	0.00416347	0.00416347	0	0	0	
+5.72	0.0042211	0.00425418	0.00425418	0	0	0	
+5.725	0.00423445	0.00434447	0.00434447	0	0	0	
+5.73	0.00424769	0.00443432	0.00443432	0	0	0	
+5.735	0.00426083	0.00452372	0.00452372	0	0	0	
+5.74	0.00427385	0.00461268	0.00461268	0	0	0	
+5.745	0.00428678	0.00470117	0.00470117	0	0	0	
+5.75	0.00429959	0.00478919	0.00478919	0	0	0	
+5.755	0.0043123	0.00487674	0.00487674	0	0	0	
+5.76	0.0043249	0.0049638	0.0049638	0	0	0	
+5.765	0.00433739	0.00505036	0.00505036	0	0	0	
+5.77	0.00434977	0.00513641	0.00513641	0	0	0	
+5.775	0.00436204	0.00522195	0.00522195	0	0	0	
+5.78	0.00437421	0.00530697	0.00530697	0	0	0	
+5.785	0.00438626	0.00539146	0.00539146	0	0	0	
+5.79	0.00439821	0.00547541	0.00547541	0	0	0	
+5.795	0.00441005	0.00555881	0.00555881	0	0	0	
+5.8	0.00442177	0.00564166	0.00564166	0	0	0	
+5.805	0.00443339	0.00572394	0.00572394	0	0	0	
+5.81	0.00444489	0.00580565	0.00580565	0	0	0	
+5.815	0.00445628	0.00588678	0.00588678	0	0	0	
+5.82	0.00446757	0.00596732	0.00596732	0	0	0	
+5.825	0.00447874	0.00604727	0.00604727	0	0	0	
+5.83	0.00448979	0.00612661	0.00612661	0	0	0	
+5.835	0.00450074	0.00620533	0.00620533	0	0	0	
+5.84	0.00451157	0.00628344	0.00628344	0	0	0	
+5.845	0.00452229	0.00636092	0.00636092	0	0	0	
+5.85	0.0045329	0.00643776	0.00643776	0	0	0	
+5.855	0.00454339	0.00651395	0.00651395	0	0	0	
+5.86	0.00455378	0.0065895	0.0065895	0	0	0	
+5.865	0.00456404	0.00666439	0.00666439	0	0	0	
+5.87	0.00457419	0.00673861	0.00673861	0	0	0	
+5.875	0.00458423	0.00681216	0.00681216	0	0	0	
+5.88	0.00459416	0.00688502	0.00688502	0	0	0	
+5.885	0.00460396	0.0069572	0.0069572	0	0	0	
+5.89	0.00461366	0.00702868	0.00702868	0	0	0	
+5.895	0.00462324	0.00709946	0.00709946	0	0	0	
+5.9	0.0046327	0.00716953	0.00716953	0	0	0	
+5.905	0.00464205	0.00723888	0.00723888	0	0	0	
+5.91	0.00465128	0.00730751	0.00730751	0	0	0	
+5.915	0.00466039	0.00737541	0.00737541	0	0	0	
+5.92	0.00466939	0.00744257	0.00744257	0	0	0	
+5.925	0.00467827	0.00750898	0.00750898	0	0	0	
+5.93	0.00468704	0.00757465	0.00757465	0	0	0	
+5.935	0.00469568	0.00763955	0.00763955	0	0	0	
+5.94	0.00470421	0.0077037	0.0077037	0	0	0	
+5.945	0.00471262	0.00776707	0.00776707	0	0	0	
+5.95	0.00472092	0.00782967	0.00782967	0	0	0	
+5.955	0.0047291	0.00789148	0.00789148	0	0	0	
+5.96	0.00473715	0.0079525	0.0079525	0	0	0	
+5.965	0.00474509	0.00801273	0.00801273	0	0	0	
+5.97	0.00475291	0.00807216	0.00807216	0	0	0	
+5.975	0.00476062	0.00813078	0.00813078	0	0	0	
+5.98	0.0047682	0.00818859	0.00818859	0	0	0	
+5.985	0.00477566	0.00824557	0.00824557	0	0	0	
+5.99	0.00478301	0.00830174	0.00830174	0	0	0	
+5.995	0.00479023	0.00835707	0.00835707	0	0	0	
+6	0.00479734	0.00841157	0.00841157	0	0	0	
+6.005	0.00480432	0.00846523	0.00846523	0	0	0	
+6.01	0.00481119	0.00851804	0.00851804	0	0	0	
+6.015	0.00481793	0.00857	0.00857	0	0	0	
+6.02	0.00482456	0.0086211	0.0086211	0	0	0	
+6.025	0.00483106	0.00867134	0.00867134	0	0	0	
+6.03	0.00483745	0.00872071	0.00872071	0	0	0	
+6.035	0.00484371	0.00876921	0.00876921	0	0	0	
+6.04	0.00484985	0.00881683	0.00881683	0	0	0	
+6.045	0.00485587	0.00886357	0.00886357	0	0	0	
+6.05	0.00486177	0.00890943	0.00890943	0	0	0	
+6.055	0.00486754	0.00895439	0.00895439	0	0	0	
+6.06	0.0048732	0.00899846	0.00899846	0	0	0	
+6.065	0.00487873	0.00904163	0.00904163	0	0	0	
+6.07	0.00488414	0.0090839	0.0090839	0	0	0	
+6.075	0.00488943	0.00912525	0.00912525	0	0	0	
+6.08	0.0048946	0.0091657	0.0091657	0	0	0	
+6.085	0.00489965	0.00920523	0.00920523	0	0	0	
+6.09	0.00490457	0.00924383	0.00924383	0	0	0	
+6.095	0.00490937	0.00928152	0.00928152	0	0	0	
+6.1	0.00491404	0.00931827	0.00931827	0	0	0	
+6.105	0.0049186	0.00935409	0.00935409	0	0	0	
+6.11	0.00492303	0.00938898	0.00938898	0	0	0	
+6.115	0.00492734	0.00942293	0.00942293	0	0	0	
+6.12	0.00493152	0.00945593	0.00945593	0	0	0	
+6.125	0.00493558	0.00948799	0.00948799	0	0	0	
+6.13	0.00493952	0.00951911	0.00951911	0	0	0	
+6.135	0.00494334	0.00954927	0.00954927	0	0	0	
+6.14	0.00494703	0.00957847	0.00957847	0	0	0	
+6.145	0.0049506	0.00960672	0.00960672	0	0	0	
+6.15	0.00495404	0.009634	0.009634	0	0	0	
+6.155	0.00495736	0.00966033	0.00966033	0	0	0	
+6.16	0.00496055	0.00968568	0.00968568	0	0	0	
+6.165	0.00496363	0.00971007	0.00971007	0	0	0	
+6.17	0.00496657	0.00973349	0.00973349	0	0	0	
+6.175	0.0049694	0.00975593	0.00975593	0	0	0	
+6.18	0.0049721	0.0097774	0.0097774	0	0	0	
+6.185	0.00497467	0.00979789	0.00979789	0	0	0	
+6.19	0.00497712	0.0098174	0.0098174	0	0	0	
+6.195	0.00497945	0.00983593	0.00983593	0	0	0	
+6.2	0.00498165	0.00985348	0.00985348	0	0	0	
+6.205	0.00498373	0.00987004	0.00987004	0	0	0	
+6.21	0.00498568	0.00988561	0.00988561	0	0	0	
+6.215	0.00498751	0.0099002	0.0099002	0	0	0	
+6.22	0.00498921	0.00991379	0.00991379	0	0	0	
+6.225	0.00499079	0.00992639	0.00992639	0	0	0	
+6.23	0.00499224	0.00993801	0.00993801	0	0	0	
+6.235	0.00499357	0.00994862	0.00994862	0	0	0	
+6.24	0.00499478	0.00995824	0.00995824	0	0	0	
+6.245	0.00499586	0.00996687	0.00996687	0	0	0	
+6.25	0.00499681	0.0099745	0.0099745	0	0	0	
+6.255	0.00499764	0.00998113	0.00998113	0	0	0	
+6.26	0.00499835	0.00998677	0.00998677	0	0	0	
+6.265	0.00499893	0.0099914	0.0099914	0	0	0	
+6.27	0.00499938	0.00999504	0.00999504	0	0	0	
+6.275	0.00499971	0.00999767	0.00999767	0	0	0	
+6.28	0.00499991	0.00999931	0.00999931	0	0	0	
+6.285	0.00499999	0.00999995	0.00999995	0	0	0	
+6.29	0.00499995	0.00999959	0.00999959	0	0	0	
+6.295	0.00499978	0.00999822	0.00999822	0	0	0	
+6.3	0.00499948	0.00999586	0.00999586	0	0	0	
+6.305	0.00499906	0.0099925	0.0099925	0	0	0	
+6.31	0.00499852	0.00998814	0.00998814	0	0	0	
+6.315	0.00499785	0.00998278	0.00998278	0	0	0	
+6.32	0.00499705	0.00997642	0.00997642	0	0	0	
+6.325	0.00499613	0.00996906	0.00996906	0	0	0	
+6.33	0.00499509	0.00996071	0.00996071	0	0	0	
+6.335	0.00499392	0.00995136	0.00995136	0	0	0	
+6.34	0.00499262	0.00994101	0.00994101	0	0	0	
+6.345	0.0049912	0.00992968	0.00992968	0	0	0	
+6.35	0.00498966	0.00991735	0.00991735	0	0	0	
+6.355	0.00498799	0.00990402	0.00990402	0	0	0	
+6.36	0.00498619	0.00988971	0.00988971	0	0	0	
+6.365	0.00498428	0.00987441	0.00987441	0	0	0	
+6.37	0.00498223	0.00985812	0.00985812	0	0	0	
+6.375	0.00498007	0.00984084	0.00984084	0	0	0	
+6.38	0.00497777	0.00982258	0.00982258	0	0	0	
+6.385	0.00497536	0.00980334	0.00980334	0	0	0	
+6.39	0.00497282	0.00978312	0.00978312	0	0	0	
+6.395	0.00497015	0.00976192	0.00976192	0	0	0	
+6.4	0.00496736	0.00973974	0.00973974	0	0	0	
+6.405	0.00496445	0.00971659	0.00971659	0	0	0	
+6.41	0.00496141	0.00969247	0.00969247	0	0	0	
+6.415	0.00495825	0.00966737	0.00966737	0	0	0	
+6.42	0.00495496	0.00964132	0.00964132	0	0	0	
+6.425	0.00495155	0.00961429	0.00961429	0	0	0	
+6.43	0.00494802	0.00958631	0.00958631	0	0	0	
+6.435	0.00494436	0.00955737	0.00955737	0	0	0	
+6.44	0.00494058	0.00952747	0.00952747	0	0	0	
+6.445	0.00493668	0.00949662	0.00949662	0	0	0	
+6.45	0.00493265	0.00946482	0.00946482	0	0	0	
+6.455	0.0049285	0.00943207	0.00943207	0	0	0	
+6.46	0.00492422	0.00939838	0.00939838	0	0	0	
+6.465	0.00491983	0.00936375	0.00936375	0	0	0	
+6.47	0.00491531	0.00932818	0.00932818	0	0	0	
+6.475	0.00491066	0.00929168	0.00929168	0	0	0	
+6.48	0.0049059	0.00925425	0.00925425	0	0	0	
+6.485	0.00490101	0.0092159	0.0092159	0	0	0	
+6.49	0.004896	0.00917662	0.00917662	0	0	0	
+6.495	0.00489086	0.00913643	0.00913643	0	0	0	
+6.5	0.00488561	0.00909532	0.00909532	0	0	0	
+6.505	0.00488023	0.00905331	0.00905331	0	0	0	
+6.51	0.00487473	0.00901039	0.00901039	0	0	0	
+6.515	0.00486911	0.00896656	0.00896656	0	0	0	
+6.52	0.00486336	0.00892184	0.00892184	0	0	0	
+6.525	0.0048575	0.00887623	0.00887623	0	0	0	
+6.53	0.00485151	0.00882973	0.00882973	0	0	0	
+6.535	0.0048454	0.00878235	0.00878235	0	0	0	
+6.54	0.00483917	0.00873409	0.00873409	0	0	0	
+6.545	0.00483282	0.00868496	0.00868496	0	0	0	
+6.55	0.00482635	0.00863496	0.00863496	0	0	0	
+6.555	0.00481976	0.00858409	0.00858409	0	0	0	
+6.56	0.00481305	0.00853237	0.00853237	0	0	0	
+6.565	0.00480622	0.00847979	0.00847979	0	0	0	
+6.57	0.00479927	0.00842636	0.00842636	0	0	0	
+6.575	0.00479219	0.0083721	0.0083721	0	0	0	
+6.58	0.004785	0.00831699	0.00831699	0	0	0	
+6.585	0.00477769	0.00826105	0.00826105	0	0	0	
+6.59	0.00477026	0.00820429	0.00820429	0	0	0	
+6.595	0.00476271	0.00814671	0.00814671	0	0	0	
+6.6	0.00475504	0.00808831	0.00808831	0	0	0	
+6.605	0.00474725	0.0080291	0.0080291	0	0	0	
+6.61	0.00473934	0.00796909	0.00796909	0	0	0	
+6.615	0.00473132	0.00790829	0.00790829	0	0	0	
+6.62	0.00472317	0.00784669	0.00784669	0	0	0	
+6.625	0.00471491	0.00778431	0.00778431	0	0	0	
+6.63	0.00470653	0.00772115	0.00772115	0	0	0	
+6.635	0.00469803	0.00765721	0.00765721	0	0	0	
+6.64	0.00468942	0.00759251	0.00759251	0	0	0	
+6.645	0.00468069	0.00752706	0.00752706	0	0	0	
+6.65	0.00467184	0.00746085	0.00746085	0	0	0	
+6.655	0.00466287	0.00739389	0.00739389	0	0	0	
+6.66	0.00465379	0.00732619	0.00732619	0	0	0	
+6.665	0.00464459	0.00725777	0.00725777	0	0	0	
+6.67	0.00463527	0.00718861	0.00718861	0	0	0	
+6.675	0.00462584	0.00711874	0.00711874	0	0	0	
+6.68	0.0046163	0.00704815	0.00704815	0	0	0	
+6.685	0.00460663	0.00697686	0.00697686	0	0	0	
+6.69	0.00459686	0.00690488	0.00690488	0	0	0	
+6.695	0.00458696	0.0068322	0.0068322	0	0	0	
+6.7	0.00457696	0.00675884	0.00675884	0	0	0	
+6.705	0.00456684	0.0066848	0.0066848	0	0	0	
+6.71	0.0045566	0.00661009	0.00661009	0	0	0	
+6.715	0.00454625	0.00653473	0.00653473	0	0	0	
+6.72	0.00453579	0.00645871	0.00645871	0	0	0	
+6.725	0.00452521	0.00638204	0.00638204	0	0	0	
+6.73	0.00451452	0.00630474	0.00630474	0	0	0	
+6.735	0.00450372	0.0062268	0.0062268	0	0	0	
+6.74	0.00449281	0.00614825	0.00614825	0	0	0	
+6.745	0.00448178	0.00606908	0.00606908	0	0	0	
+6.75	0.00447064	0.0059893	0.0059893	0	0	0	
+6.755	0.00445939	0.00590892	0.00590892	0	0	0	
+6.76	0.00444803	0.00582795	0.00582795	0	0	0	
+6.765	0.00443655	0.0057464	0.0057464	0	0	0	
+6.77	0.00442497	0.00566427	0.00566427	0	0	0	
+6.775	0.00441327	0.00558158	0.00558158	0	0	0	
+6.78	0.00440147	0.00549833	0.00549833	0	0	0	
+6.785	0.00438955	0.00541453	0.00541453	0	0	0	
+6.79	0.00437752	0.00533019	0.00533019	0	0	0	
+6.795	0.00436539	0.00524531	0.00524531	0	0	0	
+6.8	0.00435315	0.00515991	0.00515991	0	0	0	
+6.805	0.00434079	0.005074	0.005074	0	0	0	
+6.81	0.00432833	0.00498757	0.00498757	0	0	0	
+6.815	0.00431576	0.00490065	0.00490065	0	0	0	
+6.82	0.00430308	0.00481324	0.00481324	0	0	0	
+6.825	0.0042903	0.00472535	0.00472535	0	0	0	
+6.83	0.00427741	0.00463698	0.00463698	0	0	0	
+6.835	0.00426441	0.00454815	0.00454815	0	0	0	
+6.84	0.0042513	0.00445887	0.00445887	0	0	0	
+6.845	0.00423809	0.00436914	0.00436914	0	0	0	
+6.85	0.00422477	0.00427897	0.00427897	0	0	0	
+6.855	0.00421135	0.00418838	0.00418838	0	0	0	
+6.86	0.00419782	0.00409736	0.00409736	0	0	0	
+6.865	0.00418419	0.00400594	0.00400594	0	0	0	
+6.87	0.00417045	0.00391412	0.00391412	0	0	0	
+6.875	0.0041566	0.0038219	0.0038219	0	0	0	
+6.88	0.00414266	0.0037293	0.0037293	0	0	0	
+6.885	0.00412861	0.00363633	0.00363633	0	0	0	
+6.89	0.00411445	0.003543	0.003543	0	0	0	
+6.895	0.0041002	0.00344931	0.00344931	0	0	0	
+6.9	0.00408584	0.00335528	0.00335528	0	0	0	
+6.905	0.00407138	0.00326091	0.00326091	0	0	0	
+6.91	0.00405682	0.00316621	0.00316621	0	0	0	
+6.915	0.00404215	0.0030712	0.0030712	0	0	0	
+6.92	0.00402739	0.00297588	0.00297588	0	0	0	
+6.925	0.00401252	0.00288027	0.00288027	0	0	0	
+6.93	0.00399755	0.00278436	0.00278436	0	0	0	
+6.935	0.00398249	0.00268818	0.00268818	0	0	0	
+6.94	0.00396732	0.00259173	0.00259173	0	0	0	
+6.945	0.00395206	0.00249502	0.00249502	0	0	0	
+6.95	0.00393669	0.00239806	0.00239806	0	0	0	
+6.955	0.00392123	0.00230086	0.00230086	0	0	0	
+6.96	0.00390567	0.00220343	0.00220343	0	0	0	
+6.965	0.00389001	0.00210578	0.00210578	0	0	0	
+6.97	0.00387426	0.00200792	0.00200792	0	0	0	
+6.975	0.00385841	0.00190986	0.00190986	0	0	0	
+6.98	0.00384246	0.0018116	0.0018116	0	0	0	
+6.985	0.00382641	0.00171317	0.00171317	0	0	0	
+6.99	0.00381027	0.00161456	0.00161456	0	0	0	
+6.995	0.00379404	0.0015158	0.0015158	0	0	0	
+7	0.00377771	0.00141688	0.00141688	0	0	0	
+7.005	0.00376128	0.00131782	0.00131782	0	0	0	
+7.01	0.00374476	0.00121863	0.00121863	0	0	0	
+7.015	0.00372815	0.00111931	0.00111931	0	0	0	
+7.02	0.00371145	0.00101989	0.00101989	0	0	0	
+7.025	0.00369465	0.000920361	0.000920361	0	0	0	
+7.03	0.00367776	0.000820742	0.000820742	0	0	0	
+7.035	0.00366078	0.00072104	0.00072104	0	0	0	
+7.04	0.0036437	0.000621266	0.000621266	0	0	0	
+7.045	0.00362654	0.000521431	0.000521431	0	0	0	
+7.05	0.00360928	0.000421543	0.000421543	0	0	0	
+7.055	0.00359193	0.000321613	0.000321613	0	0	0	
+7.06	0.0035745	0.00022165	0.00022165	0	0	0	
+7.065	0.00355697	0.000121666	0.000121666	0	0	0	
+7.07	0.00353936	2.16693e-05	2.16693e-05	0	0	0	
+7.075	0.00352166	-7.83295e-05	-7.83295e-05	0	0	0	
+7.08	0.00350387	-0.00017832	-0.00017832	0	0	0	
+7.085	0.00348599	-0.000278293	-0.000278293	0	0	0	
+7.09	0.00346802	-0.000378239	-0.000378239	0	0	0	
+7.095	0.00344997	-0.000478146	-0.000478146	0	0	0	
+7.1	0.00343183	-0.000578006	-0.000578006	0	0	0	
+7.105	0.00341361	-0.000677808	-0.000677808	0	0	0	
+7.11	0.0033953	-0.000777542	-0.000777542	0	0	0	
+7.115	0.0033769	-0.000877198	-0.000877198	0	0	0	
+7.12	0.00335842	-0.000976767	-0.000976767	0	0	0	
+7.125	0.00333986	-0.00107624	-0.00107624	0	0	0	
+7.13	0.00332122	-0.0011756	-0.0011756	0	0	0	
+7.135	0.00330249	-0.00127485	-0.00127485	0	0	0	
+7.14	0.00328367	-0.00137396	-0.00137396	0	0	0	
+7.145	0.00326478	-0.00147295	-0.00147295	0	0	0	
+7.15	0.0032458	-0.00157178	-0.00157178	0	0	0	
+7.155	0.00322675	-0.00167046	-0.00167046	0	0	0	
+7.16	0.00320761	-0.00176896	-0.00176896	0	0	0	
+7.165	0.00318839	-0.0018673	-0.0018673	0	0	0	
+7.17	0.0031691	-0.00196544	-0.00196544	0	0	0	
+7.175	0.00314972	-0.00206339	-0.00206339	0	0	0	
+7.18	0.00313026	-0.00216113	-0.00216113	0	0	0	
+7.185	0.00311073	-0.00225866	-0.00225866	0	0	0	
+7.19	0.00309112	-0.00235596	-0.00235596	0	0	0	
+7.195	0.00307143	-0.00245303	-0.00245303	0	0	0	
+7.2	0.00305166	-0.00254985	-0.00254985	0	0	0	
+7.205	0.00303182	-0.00264641	-0.00264641	0	0	0	
+7.21	0.00301191	-0.00274271	-0.00274271	0	0	0	
+7.215	0.00299191	-0.00283874	-0.00283874	0	0	0	
+7.22	0.00297185	-0.00293448	-0.00293448	0	0	0	
+7.225	0.0029517	-0.00302993	-0.00302993	0	0	0	
+7.23	0.00293149	-0.00312508	-0.00312508	0	0	0	
+7.235	0.0029112	-0.00321991	-0.00321991	0	0	0	
+7.24	0.00289084	-0.00331442	-0.00331442	0	0	0	
+7.245	0.0028704	-0.0034086	-0.0034086	0	0	0	
+7.25	0.0028499	-0.00350244	-0.00350244	0	0	0	
+7.255	0.00282932	-0.00359593	-0.00359593	0	0	0	
+7.26	0.00280867	-0.00368906	-0.00368906	0	0	0	
+7.265	0.00278795	-0.00378182	-0.00378182	0	0	0	
+7.27	0.00276717	-0.0038742	-0.0038742	0	0	0	
+7.275	0.00274631	-0.00396619	-0.00396619	0	0	0	
+7.28	0.00272539	-0.00405779	-0.00405779	0	0	0	
+7.285	0.00270439	-0.00414898	-0.00414898	0	0	0	
+7.29	0.00268333	-0.00423976	-0.00423976	0	0	0	
+7.295	0.0026622	-0.00433011	-0.00433011	0	0	0	
+7.3	0.00264101	-0.00442004	-0.00442004	0	0	0	
+7.305	0.00261975	-0.00450951	-0.00450951	0	0	0	
+7.31	0.00259842	-0.00459854	-0.00459854	0	0	0	
+7.315	0.00257703	-0.00468711	-0.00468711	0	0	0	
+7.32	0.00255557	-0.00477521	-0.00477521	0	0	0	
+7.325	0.00253405	-0.00486283	-0.00486283	0	0	0	
+7.33	0.00251247	-0.00494996	-0.00494996	0	0	0	
+7.335	0.00249082	-0.0050366	-0.0050366	0	0	0	
+7.34	0.00246912	-0.00512274	-0.00512274	0	0	0	
+7.345	0.00244735	-0.00520836	-0.00520836	0	0	0	
+7.35	0.00242552	-0.00529347	-0.00529347	0	0	0	
+7.355	0.00240362	-0.00537804	-0.00537804	0	0	0	
+7.36	0.00238167	-0.00546208	-0.00546208	0	0	0	
+7.365	0.00235966	-0.00554557	-0.00554557	0	0	0	
+7.37	0.00233759	-0.0056285	-0.0056285	0	0	0	
+7.375	0.00231546	-0.00571088	-0.00571088	0	0	0	
+7.38	0.00229328	-0.00579268	-0.00579268	0	0	0	
+7.385	0.00227103	-0.0058739	-0.0058739	0	0	0	
+7.39	0.00224873	-0.00595453	-0.00595453	0	0	0	
+7.395	0.00222637	-0.00603457	-0.00603457	0	0	0	
+7.4	0.00220396	-0.00611401	-0.00611401	0	0	0	
+7.405	0.00218149	-0.00619283	-0.00619283	0	0	0	
+7.41	0.00215897	-0.00627104	-0.00627104	0	0	0	
+7.415	0.0021364	-0.00634862	-0.00634862	0	0	0	
+7.42	0.00211377	-0.00642556	-0.00642556	0	0	0	
+7.425	0.00209108	-0.00650186	-0.00650186	0	0	0	
+7.43	0.00206835	-0.00657751	-0.00657751	0	0	0	
+7.435	0.00204556	-0.00665251	-0.00665251	0	0	0	
+7.44	0.00202272	-0.00672683	-0.00672683	0	0	0	
+7.445	0.00199984	-0.00680049	-0.00680049	0	0	0	
+7.45	0.0019769	-0.00687346	-0.00687346	0	0	0	
+7.455	0.00195391	-0.00694575	-0.00694575	0	0	0	
+7.46	0.00193087	-0.00701734	-0.00701734	0	0	0	
+7.465	0.00190779	-0.00708823	-0.00708823	0	0	0	
+7.47	0.00188466	-0.00715842	-0.00715842	0	0	0	
+7.475	0.00186148	-0.00722788	-0.00722788	0	0	0	
+7.48	0.00183825	-0.00729663	-0.00729663	0	0	0	
+7.485	0.00181498	-0.00736464	-0.00736464	0	0	0	
+7.49	0.00179166	-0.00743192	-0.00743192	0	0	0	
+7.495	0.0017683	-0.00749845	-0.00749845	0	0	0	
+7.5	0.00174489	-0.00756424	-0.00756424	0	0	0	
+7.505	0.00172144	-0.00762927	-0.00762927	0	0	0	
+7.51	0.00169795	-0.00769353	-0.00769353	0	0	0	
+7.515	0.00167442	-0.00775703	-0.00775703	0	0	0	
+7.52	0.00165084	-0.00781975	-0.00781975	0	0	0	
+7.525	0.00162722	-0.00788169	-0.00788169	0	0	0	
+7.53	0.00160356	-0.00794284	-0.00794284	0	0	0	
+7.535	0.00157986	-0.00800319	-0.00800319	0	0	0	
+7.54	0.00155612	-0.00806275	-0.00806275	0	0	0	
+7.545	0.00153234	-0.0081215	-0.0081215	0	0	0	
+7.55	0.00150853	-0.00817943	-0.00817943	0	0	0	
+7.555	0.00148468	-0.00823655	-0.00823655	0	0	0	
+7.56	0.00146078	-0.00829285	-0.00829285	0	0	0	
+7.565	0.00143686	-0.00834832	-0.00834832	0	0	0	
+7.57	0.00141289	-0.00840295	-0.00840295	0	0	0	
+7.575	0.00138889	-0.00845674	-0.00845674	0	0	0	
+7.58	0.00136486	-0.00850968	-0.00850968	0	0	0	
+7.585	0.00134079	-0.00856178	-0.00856178	0	0	0	
+7.59	0.00131669	-0.00861302	-0.00861302	0	0	0	
+7.595	0.00129256	-0.00866339	-0.00866339	0	0	0	
+7.6	0.00126839	-0.0087129	-0.0087129	0	0	0	
+7.605	0.0012442	-0.00876154	-0.00876154	0	0	0	
+7.61	0.00121997	-0.00880931	-0.00880931	0	0	0	
+7.615	0.00119571	-0.00885619	-0.00885619	0	0	0	
+7.62	0.00117142	-0.00890219	-0.00890219	0	0	0	
+7.625	0.0011471	-0.00894729	-0.00894729	0	0	0	
+7.63	0.00112275	-0.0089915	-0.0089915	0	0	0	
+7.635	0.00109838	-0.00903482	-0.00903482	0	0	0	
+7.64	0.00107397	-0.00907723	-0.00907723	0	0	0	
+7.645	0.00104954	-0.00911873	-0.00911873	0	0	0	
+7.65	0.00102509	-0.00915932	-0.00915932	0	0	0	
+7.655	0.00100061	-0.00919899	-0.00919899	0	0	0	
+7.66	0.000976098	-0.00923775	-0.00923775	0	0	0	
+7.665	0.000951567	-0.00927558	-0.00927558	0	0	0	
+7.67	0.000927012	-0.00931248	-0.00931248	0	0	0	
+7.675	0.000902434	-0.00934845	-0.00934845	0	0	0	
+7.68	0.000877834	-0.00938349	-0.00938349	0	0	0	
+7.685	0.000853211	-0.00941758	-0.00941758	0	0	0	
+7.69	0.000828567	-0.00945074	-0.00945074	0	0	0	
+7.695	0.000803903	-0.00948295	-0.00948295	0	0	0	
+7.7	0.000779218	-0.00951421	-0.00951421	0	0	0	
+7.705	0.000754514	-0.00954453	-0.00954453	0	0	0	
+7.71	0.000729791	-0.00957388	-0.00957388	0	0	0	
+7.715	0.00070505	-0.00960228	-0.00960228	0	0	0	
+7.72	0.000680291	-0.00962972	-0.00962972	0	0	0	
+7.725	0.000655515	-0.0096562	-0.0096562	0	0	0	
+7.73	0.000630723	-0.00968171	-0.00968171	0	0	0	
+7.735	0.000605915	-0.00970625	-0.00970625	0	0	0	
+7.74	0.000581091	-0.00972983	-0.00972983	0	0	0	
+7.745	0.000556254	-0.00975242	-0.00975242	0	0	0	
+7.75	0.000531402	-0.00977405	-0.00977405	0	0	0	
+7.755	0.000506537	-0.00979469	-0.00979469	0	0	0	
+7.76	0.00048166	-0.00981436	-0.00981436	0	0	0	
+7.765	0.00045677	-0.00983305	-0.00983305	0	0	0	
+7.77	0.000431869	-0.00985075	-0.00985075	0	0	0	
+7.775	0.000406957	-0.00986747	-0.00986747	0	0	0	
+7.78	0.000382035	-0.0098832	-0.0098832	0	0	0	
+7.785	0.000357104	-0.00989794	-0.00989794	0	0	0	
+7.79	0.000332163	-0.00991169	-0.00991169	0	0	0	
+7.795	0.000307214	-0.00992445	-0.00992445	0	0	0	
+7.8	0.000282258	-0.00993622	-0.00993622	0	0	0	
+7.805	0.000257294	-0.009947	-0.009947	0	0	0	
+7.81	0.000232324	-0.00995678	-0.00995678	0	0	0	
+7.815	0.000207348	-0.00996556	-0.00996556	0	0	0	
+7.82	0.000182368	-0.00997335	-0.00997335	0	0	0	
+7.825	0.000157382	-0.00998014	-0.00998014	0	0	0	
+7.83	0.000132393	-0.00998594	-0.00998594	0	0	0	
+7.835	0.0001074	-0.00999073	-0.00999073	0	0	0	
+7.84	8.24044e-05	-0.00999453	-0.00999453	0	0	0	
+7.845	5.74068e-05	-0.00999732	-0.00999732	0	0	0	
+7.85	3.24079e-05	-0.00999912	-0.00999912	0	0	0	
+7.855	7.40816e-06	-0.00999991	-0.00999991	0	0	0	
+7.86	-1.75918e-05	-0.00999971	-0.00999971	0	0	0	
+7.865	-4.25913e-05	-0.00999851	-0.00999851	0	0	0	
+7.87	-6.75897e-05	-0.0099963	-0.0099963	0	0	0	
+7.875	-9.25864e-05	-0.0099931	-0.0099931	0	0	0	
+7.88	-0.000117581	-0.0099889	-0.0099889	0	0	0	
+7.885	-0.000142572	-0.0099837	-0.0099837	0	0	0	
+7.89	-0.00016756	-0.0099775	-0.0099775	0	0	0	
+7.895	-0.000192544	-0.0099703	-0.0099703	0	0	0	
+7.9	-0.000217523	-0.00996211	-0.00996211	0	0	0	
+7.905	-0.000242496	-0.00995291	-0.00995291	0	0	0	
+7.91	-0.000267464	-0.00994273	-0.00994273	0	0	0	
+7.915	-0.000292425	-0.00993155	-0.00993155	0	0	0	
+7.92	-0.000317378	-0.00991938	-0.00991938	0	0	0	
+7.925	-0.000342323	-0.00990621	-0.00990621	0	0	0	
+7.93	-0.00036726	-0.00989205	-0.00989205	0	0	0	
+7.935	-0.000392188	-0.00987691	-0.00987691	0	0	0	
+7.94	-0.000417106	-0.00986078	-0.00986078	0	0	0	
+7.945	-0.000442014	-0.00984366	-0.00984366	0	0	0	
+7.95	-0.00046691	-0.00982555	-0.00982555	0	0	0	
+7.955	-0.000491795	-0.00980647	-0.00980647	0	0	0	
+7.96	-0.000516667	-0.0097864	-0.0097864	0	0	0	
+7.965	-0.000541527	-0.00976536	-0.00976536	0	0	0	
+7.97	-0.000566373	-0.00974334	-0.00974334	0	0	0	
+7.975	-0.000591205	-0.00972034	-0.00972034	0	0	0	
+7.98	-0.000616022	-0.00969637	-0.00969637	0	0	0	
+7.985	-0.000640824	-0.00967144	-0.00967144	0	0	0	
+7.99	-0.000665609	-0.00964553	-0.00964553	0	0	0	
+7.995	-0.000690378	-0.00961866	-0.00961866	0	0	0	
+8	-0.00071513	-0.00959083	-0.00959083	0	0	0	
+8.005	-0.000739864	-0.00956204	-0.00956204	0	0	0	
+8.01	-0.000764579	-0.00953229	-0.00953229	0	0	0	
+8.015	-0.000789276	-0.00950159	-0.00950159	0	0	0	
+8.02	-0.000813952	-0.00946994	-0.00946994	0	0	0	
+8.025	-0.000838609	-0.00943735	-0.00943735	0	0	0	
+8.03	-0.000863244	-0.00940381	-0.00940381	0	0	0	
+8.035	-0.000887857	-0.00936933	-0.00936933	0	0	0	
+8.04	-0.000912449	-0.00933391	-0.00933391	0	0	0	
+8.045	-0.000937018	-0.00929756	-0.00929756	0	0	0	
+8.05	-0.000961563	-0.00926028	-0.00926028	0	0	0	
+8.055	-0.000986084	-0.00922207	-0.00922207	0	0	0	
+8.06	-0.00101058	-0.00918294	-0.00918294	0	0	0	
+8.065	-0.00103505	-0.00914289	-0.00914289	0	0	0	
+8.07	-0.0010595	-0.00910193	-0.00910193	0	0	0	
+8.075	-0.00108392	-0.00906006	-0.00906006	0	0	0	
+8.08	-0.00110831	-0.00901728	-0.00901728	0	0	0	
+8.085	-0.00113267	-0.0089736	-0.0089736	0	0	0	
+8.09	-0.00115701	-0.00892903	-0.00892903	0	0	0	
+8.095	-0.00118131	-0.00888356	-0.00888356	0	0	0	
+8.1	-0.00120559	-0.0088372	-0.0088372	0	0	0	
+8.105	-0.00122984	-0.00878996	-0.00878996	0	0	0	
+8.11	-0.00125406	-0.00874184	-0.00874184	0	0	0	
+8.115	-0.00127824	-0.00869284	-0.00869284	0	0	0	
+8.12	-0.00130239	-0.00864298	-0.00864298	0	0	0	
+8.125	-0.00132651	-0.00859225	-0.00859225	0	0	0	
+8.13	-0.0013506	-0.00854066	-0.00854066	0	0	0	
+8.135	-0.00137466	-0.00848822	-0.00848822	0	0	0	
+8.14	-0.00139867	-0.00843493	-0.00843493	0	0	0	
+8.145	-0.00142266	-0.00838079	-0.00838079	0	0	0	
+8.15	-0.00144661	-0.00832582	-0.00832582	0	0	0	
+8.155	-0.00147052	-0.00827002	-0.00827002	0	0	0	
+8.16	-0.0014944	-0.00821339	-0.00821339	0	0	0	
+8.165	-0.00151823	-0.00815593	-0.00815593	0	0	0	
+8.17	-0.00154204	-0.00809766	-0.00809766	0	0	0	
+8.175	-0.0015658	-0.00803859	-0.00803859	0	0	0	
+8.18	-0.00158952	-0.0079787	-0.0079787	0	0	0	
+8.185	-0.0016132	-0.00791802	-0.00791802	0	0	0	
+8.19	-0.00163685	-0.00785655	-0.00785655	0	0	0	
+8.195	-0.00166045	-0.00779429	-0.00779429	0	0	0	
+8.2	-0.00168401	-0.00773126	-0.00773126	0	0	0	
+8.205	-0.00170753	-0.00766745	-0.00766745	0	0	0	
+8.21	-0.001731	-0.00760287	-0.00760287	0	0	0	
+8.215	-0.00175443	-0.00753753	-0.00753753	0	0	0	
+8.22	-0.00177782	-0.00747144	-0.00747144	0	0	0	
+8.225	-0.00180117	-0.0074046	-0.0074046	0	0	0	
+8.23	-0.00182447	-0.00733702	-0.00733702	0	0	0	
+8.235	-0.00184772	-0.00726871	-0.00726871	0	0	0	
+8.24	-0.00187093	-0.00719967	-0.00719967	0	0	0	
+8.245	-0.00189409	-0.00712991	-0.00712991	0	0	0	
+8.25	-0.0019172	-0.00705944	-0.00705944	0	0	0	
+8.255	-0.00194026	-0.00698826	-0.00698826	0	0	0	
+8.26	-0.00196328	-0.00691639	-0.00691639	0	0	0	
+8.265	-0.00198625	-0.00684382	-0.00684382	0	0	0	
+8.27	-0.00200917	-0.00677057	-0.00677057	0	0	0	
+8.275	-0.00203203	-0.00669664	-0.00669664	0	0	0	
+8.28	-0.00205485	-0.00662204	-0.00662204	0	0	0	
+8.285	-0.00207762	-0.00654678	-0.00654678	0	0	0	
+8.29	-0.00210033	-0.00647086	-0.00647086	0	0	0	
+8.295	-0.00212299	-0.0063943	-0.0063943	0	0	0	
+8.3	-0.0021456	-0.00631709	-0.00631709	0	0	0	
+8.305	-0.00216815	-0.00623926	-0.00623926	0	0	0	
+8.31	-0.00219065	-0.0061608	-0.0061608	0	0	0	
+8.315	-0.0022131	-0.00608173	-0.00608173	0	0	0	
+8.32	-0.00223549	-0.00600204	-0.00600204	0	0	0	
+8.325	-0.00225782	-0.00592176	-0.00592176	0	0	0	
+8.33	-0.0022801	-0.00584088	-0.00584088	0	0	0	
+8.335	-0.00230232	-0.00575943	-0.00575943	0	0	0	
+8.34	-0.00232448	-0.00567739	-0.00567739	0	0	0	
+8.345	-0.00234659	-0.00559479	-0.00559479	0	0	0	
+8.35	-0.00236863	-0.00551163	-0.00551163	0	0	0	
+8.355	-0.00239062	-0.00542791	-0.00542791	0	0	0	
+8.36	-0.00241255	-0.00534366	-0.00534366	0	0	0	
+8.365	-0.00243442	-0.00525886	-0.00525886	0	0	0	
+8.37	-0.00245622	-0.00517355	-0.00517355	0	0	0	
+8.375	-0.00247797	-0.00508771	-0.00508771	0	0	0	
+8.38	-0.00249965	-0.00500137	-0.00500137	0	0	0	
+8.385	-0.00252127	-0.00491453	-0.00491453	0	0	0	
+8.39	-0.00254283	-0.00482719	-0.00482719	0	0	0	
+8.395	-0.00256432	-0.00473938	-0.00473938	0	0	0	
+8.4	-0.00258575	-0.00465109	-0.00465109	0	0	0	
+8.405	-0.00260711	-0.00456233	-0.00456233	0	0	0	
+8.41	-0.00262841	-0.00447312	-0.00447312	0	0	0	
+8.415	-0.00264965	-0.00438346	-0.00438346	0	0	0	
+8.42	-0.00267082	-0.00429336	-0.00429336	0	0	0	
+8.425	-0.00269192	-0.00420283	-0.00420283	0	0	0	
+8.43	-0.00271295	-0.00411189	-0.00411189	0	0	0	
+8.435	-0.00273392	-0.00402053	-0.00402053	0	0	0	
+8.44	-0.00275481	-0.00392877	-0.00392877	0	0	0	
+8.445	-0.00277564	-0.00383661	-0.00383661	0	0	0	
+8.45	-0.0027964	-0.00374408	-0.00374408	0	0	0	
+8.455	-0.00281709	-0.00365117	-0.00365117	0	0	0	
+8.46	-0.00283771	-0.00355789	-0.00355789	0	0	0	
+8.465	-0.00285826	-0.00346426	-0.00346426	0	0	0	
+8.47	-0.00287874	-0.00337028	-0.00337028	0	0	0	
+8.475	-0.00289914	-0.00327596	-0.00327596	0	0	0	
+8.48	-0.00291947	-0.00318132	-0.00318132	0	0	0	
+8.485	-0.00293973	-0.00308636	-0.00308636	0	0	0	
+8.49	-0.00295992	-0.00299109	-0.00299109	0	0	0	
+8.495	-0.00298003	-0.00289552	-0.00289552	0	0	0	
+8.5	-0.00300007	-0.00279966	-0.00279966	0	0	0	
+8.505	-0.00302003	-0.00270352	-0.00270352	0	0	0	
+8.51	-0.00303991	-0.00260711	-0.00260711	0	0	0	
+8.515	-0.00305973	-0.00251044	-0.00251044	0	0	0	
+8.52	-0.00307946	-0.00241352	-0.00241352	0	0	0	
+8.525	-0.00309912	-0.00231636	-0.00231636	0	0	0	
+8.53	-0.0031187	-0.00221896	-0.00221896	0	0	0	
+8.535	-0.0031382	-0.00212135	-0.00212135	0	0	0	
+8.54	-0.00315762	-0.00202352	-0.00202352	0	0	0	
+8.545	-0.00317697	-0.00192549	-0.00192549	0	0	0	
+8.55	-0.00319623	-0.00182726	-0.00182726	0	0	0	
+8.555	-0.00321542	-0.00172886	-0.00172886	0	0	0	
+8.56	-0.00323452	-0.00163028	-0.00163028	0	0	0	
+8.565	-0.00325354	-0.00153154	-0.00153154	0	0	0	
+8.57	-0.00327249	-0.00143264	-0.00143264	0	0	0	
+8.575	-0.00329135	-0.00133361	-0.00133361	0	0	0	
+8.58	-0.00331013	-0.00123443	-0.00123443	0	0	0	
+8.585	-0.00332882	-0.00113514	-0.00113514	0	0	0	
+8.59	-0.00334743	-0.00103573	-0.00103573	0	0	0	
+8.595	-0.00336596	-0.000936219	-0.000936219	0	0	0	
+8.6	-0.00338441	-0.000836613	-0.000836613	0	0	0	
+8.605	-0.00340277	-0.000736924	-0.000736924	0	0	0	
+8.61	-0.00342104	-0.000637161	-0.000637161	0	0	0	
+8.615	-0.00343923	-0.000537335	-0.000537335	0	0	0	
+8.62	-0.00345733	-0.000437454	-0.000437454	0	0	0	
+8.625	-0.00347535	-0.00033753	-0.00033753	0	0	0	
+8.63	-0.00349328	-0.000237573	-0.000237573	0	0	0	
+8.635	-0.00351112	-0.000137591	-0.000137591	0	0	0	
+8.64	-0.00352888	-3.75957e-05	-3.75957e-05	0	0	0	
+8.645	-0.00354654	6.24034e-05	6.24034e-05	0	0	0	
+8.65	-0.00356412	0.000162396	0.000162396	0	0	0	
+8.655	-0.00358161	0.000262373	0.000262373	0	0	0	
+8.66	-0.00359901	0.000362323	0.000362323	0	0	0	
+8.665	-0.00361632	0.000462237	0.000462237	0	0	0	
+8.67	-0.00363354	0.000562105	0.000562105	0	0	0	
+8.675	-0.00365067	0.000661917	0.000661917	0	0	0	
+8.68	-0.0036677	0.000761663	0.000761663	0	0	0	
+8.685	-0.00368465	0.000861332	0.000861332	0	0	0	
+8.69	-0.0037015	0.000960915	0.000960915	0	0	0	
+8.695	-0.00371826	0.0010604	0.0010604	0	0	0	
+8.7	-0.00373493	0.00115978	0.00115978	0	0	0	
+8.705	-0.0037515	0.00125905	0.00125905	0	0	0	
+8.71	-0.00376799	0.00135819	0.00135819	0	0	0	
+8.715	-0.00378437	0.00145719	0.00145719	0	0	0	
+8.72	-0.00380066	0.00155605	0.00155605	0	0	0	
+8.725	-0.00381686	0.00165475	0.00165475	0	0	0	
+8.73	-0.00383296	0.00175329	0.00175329	0	0	0	
+8.735	-0.00384897	0.00185165	0.00185165	0	0	0	
+8.74	-0.00386488	0.00194982	0.00194982	0	0	0	
+8.745	-0.00388069	0.00204781	0.00204781	0	0	0	
+8.75	-0.0038964	0.00214558	0.00214558	0	0	0	
+8.755	-0.00391202	0.00224314	0.00224314	0	0	0	
+8.76	-0.00392754	0.00234048	0.00234048	0	0	0	
+8.765	-0.00394296	0.00243758	0.00243758	0	0	0	
+8.77	-0.00395829	0.00253444	0.00253444	0	0	0	
+8.775	-0.00397351	0.00263105	0.00263105	0	0	0	
+8.78	-0.00398864	0.00272739	0.00272739	0	0	0	
+8.785	-0.00400366	0.00282346	0.00282346	0	0	0	
+8.79	-0.00401859	0.00291925	0.00291925	0	0	0	
+8.795	-0.00403341	0.00301475	0.00301475	0	0	0	
+8.8	-0.00404814	0.00310994	0.00310994	0	0	0	
+8.805	-0.00406276	0.00320483	0.00320483	0	0	0	
+8.81	-0.00407728	0.00329939	0.00329939	0	0	0	
+8.815	-0.0040917	0.00339362	0.00339362	0	0	0	
+8.82	-0.00410602	0.00348752	0.00348752	0	0	0	
+8.825	-0.00412023	0.00358106	0.00358106	0	0	0	
+8.83	-0.00413434	0.00367425	0.00367425	0	0	0	
+8.835	-0.00414835	0.00376707	0.00376707	0	0	0	
+8.84	-0.00416226	0.00385951	0.00385951	0	0	0	
+8.845	-0.00417606	0.00395157	0.00395157	0	0	0	
+8.85	-0.00418975	0.00404323	0.00404323	0	0	0	
+8.855	-0.00420334	0.00413449	0.00413449	0	0	0	
+8.86	-0.00421683	0.00422533	0.00422533	0	0	0	
+8.865	-0.00423021	0.00431575	0.00431575	0	0	0	
+8.87	-0.00424348	0.00440574	0.00440574	0	0	0	
+8.875	-0.00425665	0.00449529	0.00449529	0	0	0	
+8.88	-0.00426972	0.00458439	0.00458439	0	0	0	
+8.885	-0.00428267	0.00467303	0.00467303	0	0	0	
+8.89	-0.00429552	0.00476121	0.00476121	0	0	0	
+8.895	-0.00430826	0.00484891	0.00484891	0	0	0	
+8.9	-0.0043209	0.00493612	0.00493612	0	0	0	
+8.905	-0.00433342	0.00502284	0.00502284	0	0	0	
+8.91	-0.00434584	0.00510906	0.00510906	0	0	0	
+8.915	-0.00435815	0.00519476	0.00519476	0	0	0	
+8.92	-0.00437035	0.00527995	0.00527995	0	0	0	
+8.925	-0.00438244	0.00536461	0.00536461	0	0	0	
+8.93	-0.00439442	0.00544873	0.00544873	0	0	0	
+8.935	-0.00440629	0.00553231	0.00553231	0	0	0	
+8.94	-0.00441805	0.00561533	0.00561533	0	0	0	
+8.945	-0.0044297	0.0056978	0.0056978	0	0	0	
+8.95	-0.00444124	0.00577969	0.00577969	0	0	0	
+8.955	-0.00445267	0.005861	0.005861	0	0	0	
+8.96	-0.00446398	0.00594173	0.00594173	0	0	0	
+8.965	-0.00447519	0.00602187	0.00602187	0	0	0	
+8.97	-0.00448628	0.0061014	0.0061014	0	0	0	
+8.975	-0.00449726	0.00618032	0.00618032	0	0	0	
+8.98	-0.00450813	0.00625863	0.00625863	0	0	0	
+8.985	-0.00451889	0.0063363	0.0063363	0	0	0	
+8.99	-0.00452953	0.00641335	0.00641335	0	0	0	
+8.995	-0.00454006	0.00648975	0.00648975	0	0	0	
+9	-0.00455048	0.00656551	0.00656551	0	0	0	
+9.005	-0.00456078	0.00664061	0.00664061	0	0	0	
+9.01	-0.00457097	0.00671504	0.00671504	0	0	0	
+9.015	-0.00458105	0.0067888	0.0067888	0	0	0	
+9.02	-0.00459101	0.00686189	0.00686189	0	0	0	
+9.025	-0.00460085	0.00693428	0.00693428	0	0	0	
+9.03	-0.00461058	0.00700599	0.00700599	0	0	0	
+9.035	-0.0046202	0.00707699	0.00707699	0	0	0	
+9.04	-0.0046297	0.00714729	0.00714729	0	0	0	
+9.045	-0.00463908	0.00721687	0.00721687	0	0	0	
+9.05	-0.00464835	0.00728573	0.00728573	0	0	0	
+9.055	-0.0046575	0.00735386	0.00735386	0	0	0	
+9.06	-0.00466654	0.00742125	0.00742125	0	0	0	
+9.065	-0.00467545	0.00748791	0.00748791	0	0	0	
+9.07	-0.00468426	0.00755381	0.00755381	0	0	0	
+9.075	-0.00469294	0.00761896	0.00761896	0	0	0	
+9.08	-0.00470151	0.00768335	0.00768335	0	0	0	
+9.085	-0.00470996	0.00774697	0.00774697	0	0	0	
+9.09	-0.00471829	0.00780981	0.00780981	0	0	0	
+9.095	-0.0047265	0.00787187	0.00787187	0	0	0	
+9.1	-0.0047346	0.00793315	0.00793315	0	0	0	
+9.105	-0.00474258	0.00799363	0.00799363	0	0	0	
+9.11	-0.00475044	0.00805332	0.00805332	0	0	0	
+9.115	-0.00475818	0.00811219	0.00811219	0	0	0	
+9.12	-0.0047658	0.00817026	0.00817026	0	0	0	
+9.125	-0.0047733	0.00822751	0.00822751	0	0	0	
+9.13	-0.00478068	0.00828394	0.00828394	0	0	0	
+9.135	-0.00478795	0.00833954	0.00833954	0	0	0	
+9.14	-0.00479509	0.0083943	0.0083943	0	0	0	
+9.145	-0.00480211	0.00844823	0.00844823	0	0	0	
+9.15	-0.00480902	0.00850131	0.00850131	0	0	0	
+9.155	-0.0048158	0.00855354	0.00855354	0	0	0	
+9.16	-0.00482246	0.00860491	0.00860491	0	0	0	
+9.165	-0.004829	0.00865543	0.00865543	0	0	0	
+9.17	-0.00483543	0.00870508	0.00870508	0	0	0	
+9.175	-0.00484173	0.00875386	0.00875386	0	0	0	
+9.18	-0.00484791	0.00880176	0.00880176	0	0	0	
+9.185	-0.00485396	0.00884878	0.00884878	0	0	0	
+9.19	-0.0048599	0.00889492	0.00889492	0	0	0	
+9.195	-0.00486572	0.00894017	0.00894017	0	0	0	
+9.2	-0.00487141	0.00898452	0.00898452	0	0	0	
+9.205	-0.00487698	0.00902798	0.00902798	0	0	0	
+9.21	-0.00488243	0.00907053	0.00907053	0	0	0	
+9.215	-0.00488776	0.00911218	0.00911218	0	0	0	
+9.22	-0.00489297	0.00915291	0.00915291	0	0	0	
+9.225	-0.00489805	0.00919273	0.00919273	0	0	0	
+9.23	-0.00490301	0.00923164	0.00923164	0	0	0	
+9.235	-0.00490785	0.00926961	0.00926961	0	0	0	
+9.24	-0.00491257	0.00930666	0.00930666	0	0	0	
+9.245	-0.00491716	0.00934278	0.00934278	0	0	0	
+9.25	-0.00492163	0.00937797	0.00937797	0	0	0	
+9.255	-0.00492598	0.00941222	0.00941222	0	0	0	
+9.26	-0.0049302	0.00944552	0.00944552	0	0	0	
+9.265	-0.0049343	0.00947788	0.00947788	0	0	0	
+9.27	-0.00493828	0.0095093	0.0095093	0	0	0	
+9.275	-0.00494214	0.00953976	0.00953976	0	0	0	
+9.28	-0.00494587	0.00956927	0.00956927	0	0	0	
+9.285	-0.00494947	0.00959782	0.00959782	0	0	0	
+9.29	-0.00495296	0.00962542	0.00962542	0	0	0	
+9.295	-0.00495631	0.00965205	0.00965205	0	0	0	
+9.3	-0.00495955	0.00967771	0.00967771	0	0	0	
+9.305	-0.00496266	0.00970241	0.00970241	0	0	0	
+9.31	-0.00496565	0.00972614	0.00972614	0	0	0	
+9.315	-0.00496851	0.00974889	0.00974889	0	0	0	
+9.32	-0.00497125	0.00977067	0.00977067	0	0	0	
+9.325	-0.00497387	0.00979147	0.00979147	0	0	0	
+9.33	-0.00497636	0.0098113	0.0098113	0	0	0	
+9.335	-0.00497872	0.00983014	0.00983014	0	0	0	
+9.34	-0.00498096	0.009848	0.009848	0	0	0	
+9.345	-0.00498308	0.00986487	0.00986487	0	0	0	
+9.35	-0.00498507	0.00988076	0.00988076	0	0	0	
+9.355	-0.00498694	0.00989566	0.00989566	0	0	0	
+9.36	-0.00498868	0.00990957	0.00990957	0	0	0	
+9.365	-0.0049903	0.00992249	0.00992249	0	0	0	
+9.37	-0.0049918	0.00993442	0.00993442	0	0	0	
+9.375	-0.00499316	0.00994535	0.00994535	0	0	0	
+9.38	-0.00499441	0.00995529	0.00995529	0	0	0	
+9.385	-0.00499553	0.00996423	0.00996423	0	0	0	
+9.39	-0.00499652	0.00997218	0.00997218	0	0	0	
+9.395	-0.00499739	0.00997913	0.00997913	0	0	0	
+9.4	-0.00499813	0.00998508	0.00998508	0	0	0	
+9.405	-0.00499875	0.00999003	0.00999003	0	0	0	
+9.41	-0.00499925	0.00999399	0.00999399	0	0	0	
+9.415	-0.00499962	0.00999694	0.00999694	0	0	0	
+9.42	-0.00499986	0.0099989	0.0099989	0	0	0	
+9.425	-0.00499998	0.00999985	0.00999985	0	0	0	
+9.43	-0.00499998	0.00999981	0.00999981	0	0	0	
+9.435	-0.00499985	0.00999877	0.00999877	0	0	0	
+9.44	-0.00499959	0.00999672	0.00999672	0	0	0	
+9.445	-0.00499921	0.00999368	0.00999368	0	0	0	
+9.45	-0.0049987	0.00998963	0.00998963	0	0	0	
+9.455	-0.00499807	0.00998459	0.00998459	0	0	0	
+9.46	-0.00499732	0.00997855	0.00997855	0	0	0	
+9.465	-0.00499644	0.00997151	0.00997151	0	0	0	
+9.47	-0.00499543	0.00996348	0.00996348	0	0	0	
+9.475	-0.0049943	0.00995445	0.00995445	0	0	0	
+9.48	-0.00499305	0.00994442	0.00994442	0	0	0	
+9.485	-0.00499167	0.0099334	0.0099334	0	0	0	
+9.49	-0.00499016	0.00992138	0.00992138	0	0	0	
+9.495	-0.00498853	0.00990837	0.00990837	0	0	0	
+9.5	-0.00498678	0.00989438	0.00989438	0	0	0	
+9.505	-0.0049849	0.00987939	0.00987939	0	0	0	
+9.51	-0.0049829	0.00986341	0.00986341	0	0	0	
+9.515	-0.00498077	0.00984645	0.00984645	0	0	0	
+9.52	-0.00497852	0.0098285	0.0098285	0	0	0	
+9.525	-0.00497614	0.00980957	0.00980957	0	0	0	
+9.53	-0.00497364	0.00978966	0.00978966	0	0	0	
+9.535	-0.00497101	0.00976877	0.00976877	0	0	0	
+9.54	-0.00496826	0.00974691	0.00974691	0	0	0	
+9.545	-0.00496539	0.00972407	0.00972407	0	0	0	
+9.55	-0.00496239	0.00970025	0.00970025	0	0	0	
+9.555	-0.00495927	0.00967547	0.00967547	0	0	0	
+9.56	-0.00495602	0.00964972	0.00964972	0	0	0	
+9.565	-0.00495265	0.00962301	0.00962301	0	0	0	
+9.57	-0.00494916	0.00959533	0.00959533	0	0	0	
+9.575	-0.00494554	0.00956669	0.00956669	0	0	0	
+9.58	-0.0049418	0.0095371	0.0095371	0	0	0	
+9.585	-0.00493793	0.00950655	0.00950655	0	0	0	
+9.59	-0.00493394	0.00947505	0.00947505	0	0	0	
+9.595	-0.00492983	0.0094426	0.0094426	0	0	0	
+9.6	-0.0049256	0.00940921	0.00940921	0	0	0	
+9.605	-0.00492124	0.00937488	0.00937488	0	0	0	
+9.61	-0.00491676	0.00933961	0.00933961	0	0	0	
+9.615	-0.00491215	0.00930341	0.00930341	0	0	0	
+9.62	-0.00490743	0.00926628	0.00926628	0	0	0	
+9.625	-0.00490258	0.00922822	0.00922822	0	0	0	
+9.63	-0.00489761	0.00918924	0.00918924	0	0	0	
+9.635	-0.00489251	0.00914933	0.00914933	0	0	0	
+9.64	-0.00488729	0.00910852	0.00910852	0	0	0	
+9.645	-0.00488196	0.00906679	0.00906679	0	0	0	
+9.65	-0.00487649	0.00902416	0.00902416	0	0	0	
+9.655	-0.00487091	0.00898062	0.00898062	0	0	0	
+9.66	-0.00486521	0.00893619	0.00893619	0	0	0	
+9.665	-0.00485938	0.00889086	0.00889086	0	0	0	
+9.67	-0.00485343	0.00884464	0.00884464	0	0	0	
+9.675	-0.00484736	0.00879754	0.00879754	0	0	0	
+9.68	-0.00484117	0.00874956	0.00874956	0	0	0	
+9.685	-0.00483486	0.0087007	0.0087007	0	0	0	
+9.69	-0.00482843	0.00865098	0.00865098	0	0	0	
+9.695	-0.00482187	0.00860039	0.00860039	0	0	0	
+9.7	-0.0048152	0.00854893	0.00854893	0	0	0	
+9.705	-0.00480841	0.00849663	0.00849663	0	0	0	
+9.71	-0.00480149	0.00844347	0.00844347	0	0	0	
+9.715	-0.00479446	0.00838947	0.00838947	0	0	0	
+9.72	-0.0047873	0.00833463	0.00833463	0	0	0	
+9.725	-0.00478003	0.00827896	0.00827896	0	0	0	
+9.73	-0.00477264	0.00822246	0.00822246	0	0	0	
+9.735	-0.00476513	0.00816514	0.00816514	0	0	0	
+9.74	-0.00475749	0.008107	0.008107	0	0	0	
+9.745	-0.00474974	0.00804805	0.00804805	0	0	0	
+9.75	-0.00474187	0.00798829	0.00798829	0	0	0	
+9.755	-0.00473389	0.00792774	0.00792774	0	0	0	
+9.76	-0.00472578	0.00786639	0.00786639	0	0	0	
+9.765	-0.00471755	0.00780426	0.00780426	0	0	0	
+9.77	-0.00470921	0.00774135	0.00774135	0	0	0	
+9.775	-0.00470075	0.00767766	0.00767766	0	0	0	
+9.78	-0.00469217	0.00761321	0.00761321	0	0	0	
+9.785	-0.00468348	0.00754799	0.00754799	0	0	0	
+9.79	-0.00467467	0.00748202	0.00748202	0	0	0	
+9.795	-0.00466574	0.0074153	0.0074153	0	0	0	
+9.8	-0.00465669	0.00734784	0.00734784	0	0	0	
+9.805	-0.00464753	0.00727964	0.00727964	0	0	0	
+9.81	-0.00463825	0.00721072	0.00721072	0	0	0	
+9.815	-0.00462886	0.00714107	0.00714107	0	0	0	
+9.82	-0.00461935	0.00707071	0.00707071	0	0	0	
+9.825	-0.00460972	0.00699965	0.00699965	0	0	0	
+9.83	-0.00459998	0.00692788	0.00692788	0	0	0	
+9.835	-0.00459013	0.00685542	0.00685542	0	0	0	
+9.84	-0.00458016	0.00678228	0.00678228	0	0	0	
+9.845	-0.00457007	0.00670846	0.00670846	0	0	0	
+9.85	-0.00455987	0.00663396	0.00663396	0	0	0	
+9.855	-0.00454956	0.00655881	0.00655881	0	0	0	
+9.86	-0.00453913	0.00648299	0.00648299	0	0	0	
+9.865	-0.00452859	0.00640653	0.00640653	0	0	0	
+9.87	-0.00451794	0.00632943	0.00632943	0	0	0	
+9.875	-0.00450717	0.0062517	0.0062517	0	0	0	
+9.88	-0.00449629	0.00617334	0.00617334	0	0	0	
+9.885	-0.0044853	0.00609436	0.00609436	0	0	0	
+9.89	-0.0044742	0.00601477	0.00601477	0	0	0	
+9.895	-0.00446298	0.00593459	0.00593459	0	0	0	
+9.9	-0.00445166	0.0058538	0.0058538	0	0	0	
+9.905	-0.00444022	0.00577244	0.00577244	0	0	0	
+9.91	-0.00442867	0.00569049	0.00569049	0	0	0	
+9.915	-0.00441701	0.00560798	0.00560798	0	0	0	
+9.92	-0.00440524	0.00552491	0.00552491	0	0	0	
+9.925	-0.00439336	0.00544128	0.00544128	0	0	0	
+9.93	-0.00438137	0.00535711	0.00535711	0	0	0	
+9.935	-0.00436927	0.0052724	0.0052724	0	0	0	
+9.94	-0.00435706	0.00518717	0.00518717	0	0	0	
+9.945	-0.00434474	0.00510142	0.00510142	0	0	0	
+9.95	-0.00433231	0.00501516	0.00501516	0	0	0	
+9.955	-0.00431978	0.00492839	0.00492839	0	0	0	
+9.96	-0.00430713	0.00484114	0.00484114	0	0	0	
+9.965	-0.00429438	0.0047534	0.0047534	0	0	0	
+9.97	-0.00428153	0.00466518	0.00466518	0	0	0	
+9.975	-0.00426856	0.0045765	0.0045765	0	0	0	
+9.98	-0.00425549	0.00448736	0.00448736	0	0	0	
+9.985	-0.00424231	0.00439777	0.00439777	0	0	0	
+9.99	-0.00422903	0.00430774	0.00430774	0	0	0	
+9.995	-0.00421564	0.00421728	0.00421728	0	0	0	
+10	-0.00420214	0.0041264	0.0041264	0	0	0	
diff --git a/src/test/data/IMU/odom_static15s.txt b/src/test/data/IMU/odom_static15s.txt
new file mode 100644
index 0000000000000000000000000000000000000000..b579472180d800f0285e94a30bbfe776f9a4ec06
--- /dev/null
+++ b/src/test/data/IMU/odom_static15s.txt
@@ -0,0 +1,5 @@
+1.003480	0	0	0	0	0	0
+4.222293	0	0	0	0	0	0
+8.398237	0	0	0	0	0	0
+11.319065	0	0	0	0	0	0
+14.997002	0	0	0	0	0	0
diff --git a/src/test/data/IMU/odom_trajectory_full.txt b/src/test/data/IMU/odom_trajectory_full.txt
new file mode 100644
index 0000000000000000000000000000000000000000..9abc884a6ea287bf5bfdebdbf619f1f810d8a537
--- /dev/null
+++ b/src/test/data/IMU/odom_trajectory_full.txt
@@ -0,0 +1,2 @@
+0.8412410790681586	0.9078813409296691	0.9078813409296682	0.9798229920277438	0.1359776688450156	0.0544507118249929	0.1359856531073395	0.5398816086838777	-0.8341113238499829	-0.8341113238499744	
+1.0000000000000000	0.8412410790681586	0.9078813409296691	0.9078813409296682	0.2737993103284272	0.1096398215325155	0.2738153871264509	
diff --git a/src/test/gtest_constraint_fix.cpp b/src/test/gtest_constraint_fix.cpp
index 770bf678db6d15e759bf5de7157d05276da838b3..eaa454d6aec4a8a0a7857587940d7bc9ea66b3eb 100644
--- a/src/test/gtest_constraint_fix.cpp
+++ b/src/test/gtest_constraint_fix.cpp
@@ -20,12 +20,12 @@ using std::cout;
 using std::endl;
 
 // Input data and covariance
-Vector3s pose6(Vector3s::Random());
+Vector3s pose(Vector3s::Random());
 Vector3s data_var((Vector3s() << 0.2,0.2,0.2).finished());
 Matrix3s data_cov = data_var.asDiagonal();
 
 // perturbated priors
-Vector3s x0 = pose6 + Vector3s::Random()*0.25;
+Vector3s x0 = pose + Vector3s::Random()*0.25;
 
 // Problem and solver
 ProblemPtr problem = Problem::create("PO 2D");
@@ -35,10 +35,9 @@ CeresManager ceres_mgr(problem);
 FrameBasePtr frm0 = problem->emplaceFrame(KEY_FRAME, problem->zeroState(), TimeStamp(0));
 
 // Capture, feature and constraint from frm1 to frm0
-CaptureBasePtr cap0 = frm0->addCapture(std::make_shared<CaptureMotion>(0, nullptr, pose6, 7, 6));
-FeatureBasePtr fea0 = cap0->addFeature(std::make_shared<FeatureBase>("ODOM 3D", pose6, data_cov));
+CaptureBasePtr cap0 = frm0->addCapture(std::make_shared<CaptureMotion>(0, nullptr, pose, 3, 3, 3, 0));
+FeatureBasePtr fea0 = cap0->addFeature(std::make_shared<FeatureBase>("ODOM 2D", pose, data_cov));
 ConstraintFixPtr ctr0 = std::static_pointer_cast<ConstraintFix>(fea0->addConstraint(std::make_shared<ConstraintFix>(fea0)));
-ConstraintBasePtr dummy = frm0->addConstrainedBy(ctr0);
 
 ////////////////////////////////////////////////////////
 
@@ -62,7 +61,7 @@ TEST(ConstraintFix, solve)
     // solve for frm0
     std::string report = ceres_mgr.solve(0); // 0: nothing, 1: BriefReport, 2: FullReport
 
-    ASSERT_MATRIX_APPROX(frm0->getState(), pose6, 1e-6);
+    ASSERT_MATRIX_APPROX(frm0->getState(), pose, 1e-6);
 
 }
 
diff --git a/src/test/gtest_constraint_fix_3D.cpp b/src/test/gtest_constraint_fix_3D.cpp
index 16c3498244d336fb3dfcf797d88e5777f02ab083..126b1a081f5a8c731a8355dba8106ddd9ff5a0a7 100644
--- a/src/test/gtest_constraint_fix_3D.cpp
+++ b/src/test/gtest_constraint_fix_3D.cpp
@@ -26,13 +26,13 @@ Vector7s pose6toPose7(Vector6s _pose6)
 
 
 // Input pose6 and covariance
-Vector6s pose6(Vector6s::Random());
-Vector7s pose7 = pose6toPose7(pose6);
+Vector6s pose(Vector6s::Random());
+Vector7s pose7 = pose6toPose7(pose);
 Vector6s data_var((Vector6s() << 0.2,0.2,0.2,0.2,0.2,0.2).finished());
 Matrix6s data_cov = data_var.asDiagonal();
 
 // perturbated priors
-Vector7s x0 = pose6toPose7(pose6 + Vector6s::Random()*0.25);
+Vector7s x0 = pose6toPose7(pose + Vector6s::Random()*0.25);
 
 // Problem and solver
 ProblemPtr problem = Problem::create("PO 3D");
@@ -42,10 +42,9 @@ CeresManager ceres_mgr(problem);
 FrameBasePtr frm0 = problem->emplaceFrame(KEY_FRAME, problem->zeroState(), TimeStamp(0));
 
 // Capture, feature and constraint
-CaptureBasePtr cap0 = frm0->addCapture(std::make_shared<CaptureMotion>(0, nullptr, pose7, 7, 6));
+CaptureBasePtr cap0 = frm0->addCapture(std::make_shared<CaptureMotion>(0, nullptr, pose7, 7, 7, 6, 0));
 FeatureBasePtr fea0 = cap0->addFeature(std::make_shared<FeatureBase>("ODOM 3D", pose7, data_cov));
 ConstraintFix3DPtr ctr0 = std::static_pointer_cast<ConstraintFix3D>(fea0->addConstraint(std::make_shared<ConstraintFix3D>(fea0)));
-ConstraintBasePtr dummy = frm0->addConstrainedBy(ctr0);
 
 
 ////////////////////////////////////////////////////////
diff --git a/src/test/gtest_constraint_imu.cpp b/src/test/gtest_constraint_imu.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..df20ddcd493824717bc9aa3068a6f5c15fa1f545
--- /dev/null
+++ b/src/test/gtest_constraint_imu.cpp
@@ -0,0 +1,4438 @@
+/**
+ * \file gtest_constraint_imu.cpp
+ *
+ *  Created on: Jan 01, 2017
+ *      \author: Dinesh Atchuthan
+ */
+
+//Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "sensor_imu.h"
+#include "capture_imu.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu.h"
+#include "processor_odom_3D.h"
+#include "ceres_wrapper/ceres_manager.h"
+#include "constraint_fix_3D.h"
+
+#include "utils_gtest.h"
+#include "../src/logging.h"
+
+#include <iostream>
+#include <fstream>
+
+//#define GET_RESIDUALS
+
+using namespace Eigen;
+using namespace std;
+using namespace wolf;
+
+/*
+ * This test is designed to test IMU biases in a particular case : perfect IMU, not moving.
+ * var(b1,b2,p2,v2,q2), inv(p1,q1,v1); fac1: imu+(b1=b2)
+ * So there is no odometry data.
+ * IMU data file should first contain initial conditions, then the time_step between each new imu and the last one (in seconds) data,
+ * and finally the last stateafter integration and the last timestamp, Then it should contain all IMU data and related timestamps
+ */
+
+class ConstraintIMU_biasTest_Static_NullBias : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        expected_final_state = x_origin; //null bias + static
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+
+
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu;
+        data_imu << -wolf::gravity(), 0,0,0;
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu); //set data on IMU (measure only gravity here)
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state); //We expect to find this solution, this can be perturbated in following tests
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Static_NonNullAccBias : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+        origin_bias << 0.002, 0.005, 0.1, 0,0,0;
+        //origin_bias << 0.002, 0.005, 0.1, 0.07,-0.035,-0.1;
+
+        expected_final_state = x_origin; //null bias + static
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu;
+        data_imu << -wolf::gravity(), 0,0,0;
+        data_imu = data_imu + origin_bias;
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu); //set data on IMU (measure only gravity here)
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state); //We expect to find this solution, this can be perturbated in following tests
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Static_NonNullGyroBias : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+        origin_bias << 0, 0,0, 0.07,-0.035,-0.1;
+        //origin_bias << 0.002, 0.005, 0.1, 0.07,-0.035,-0.1;
+
+        expected_final_state = x_origin; //null bias + static, 
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu;
+        data_imu << -wolf::gravity(), 0,0,0;
+        data_imu = data_imu + origin_bias;
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu); //set data on IMU (measure only gravity here)
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state); //We expect to find this solution, this can be perturbated in following tests
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Static_NonNullBias : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+        origin_bias << 0.002, 0.005, 0.1, 0.07,-0.035,-0.1;
+
+        expected_final_state = x_origin; //null bias + static, 
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu;
+        data_imu << -wolf::gravity(), 0,0,0;
+        data_imu = data_imu + origin_bias;
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu); //set data on IMU (measure only gravity here)
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state); //We expect to find this solution, this can be perturbated in following tests
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Move_NullBias : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        Eigen::Vector6s data_imu;
+        data_imu << 0,10,-wolf::gravity()(2), 0,0,0; //10m/s on y direction
+        expected_final_state << 0,5,0, 0,0,0,1, 0,10,0, 0,0,0, 0,0,0; // advanced at a=10m/s2 during 1s ==> dx = 0.5*10*1^2 = 5; dvx = 10*1 = 10
+
+        origin_bias<< 0,0,0,0,0,0;
+
+        expected_final_state = x_origin;
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+
+
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu);
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Move_NonNullBias : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        Eigen::Vector6s data_imu;
+        origin_bias = Eigen::Vector6s::Random();
+        data_imu << 0,10,-wolf::gravity()(2), 0,0,0; //10m/s on y direction
+        data_imu = data_imu + origin_bias;
+        expected_final_state << 0,5,0, 0,0,0,1, 0,10,0, 0,0,0, 0,0,0; // advanced at a=10m/s2 during 1s ==> dx = 0.5*10*1^2 = 5; dvx = 10*1 = 10
+
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu);
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Move_NonNullBiasRotCst : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        Eigen::Vector6s data_imu, data_imu_initial;
+        origin_bias = Eigen::Vector6s::Random();
+        wolf::Scalar rate_of_turn = 5 * M_PI/180.0; // rad/s
+        data_imu << -wolf::gravity(), rate_of_turn,0,0; //rotation only
+        data_imu_initial = data_imu;
+
+        // Expected state after one second integration
+        Eigen::Quaternions quat_comp(Eigen::Quaternions::Identity());
+        quat_comp = quat_comp * wolf::v2q(data_imu.tail(3)*1);
+        expected_final_state << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, 0,0,0, 0,0,0; // rotated at 5 deg/s for 0.1s = 5 deg => 5 * M_PI/180
+
+        data_imu = data_imu + origin_bias; // bias measurements
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu);
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            //gravity measure depends on current IMU orientation + bias
+            //use data_imu_initial to measure gravity from real orientation of IMU then add biases
+            data_imu.head(3) = (v2q(data_imu_initial.tail(3) * t.get()).conjugate() * data_imu_initial.head(3)) + origin_bias.head(3);
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setData(data_imu);
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_biasTest_Move_NonNullBiasRotAndVCst : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 10,-3,4, 0,0,0, 0,0,0;
+        t.set(0);
+
+        Eigen::Vector6s data_imu, data_imu_initial;
+        origin_bias = Eigen::Vector6s::Random();
+        origin_bias << 0,0,0, 0,0,0;
+        wolf::Scalar rate_of_turn = 5 * M_PI/180.0; // rad/s
+        data_imu << -wolf::gravity(), rate_of_turn,0,0; //rotation only
+        data_imu_initial = data_imu;
+
+        // Expected state after one second integration
+        Eigen::Quaternions quat_comp(Eigen::Quaternions::Identity());
+        quat_comp = quat_comp * wolf::v2q(data_imu.tail(3)*1);
+
+        // rotated at 5 deg/s for 1s = 5 deg => 5 * M_PI/180
+        // no other acceleration : we should still be moving at initial velocity
+        // position = V*dt, dt = 1s
+        expected_final_state << 10,-3,4, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 10,-3,4, 0,0,0, 0,0,0;
+
+        data_imu = data_imu + origin_bias; // bias measurements
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(t, sen_imu, data_imu);
+
+        for(unsigned int i = 0; i < 1000; i++) //integrate during 1 second
+        {
+            //gravity measure depends on current IMU orientation + bias
+            //use data_imu_initial to measure gravity from real orientation of IMU then add biases
+            data_imu.head(3) = (v2q(data_imu_initial.tail(3) * t.get()).conjugate() * data_imu_initial.head(3)) + origin_bias.head(3);
+            t.set(t.get() + 0.001); //increment of 1 ms
+            imu_ptr->setData(data_imu);
+            imu_ptr->setTimeStamp(t);
+
+            // process data in capture
+            sen_imu->process(imu_ptr);
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+// var(b1,b2), inv(p1,q1,v1,p2,q2,v2); fac1: imu(p,q,v)+(b1=b2)
+
+class ConstraintIMU_biasTest_Move_NonNullBiasRot : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION;
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t1.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        origin_bias << 0.0015, 0.004, -0.002, 0.005, -0.0074, -0.003;
+        t.set(0);
+        Eigen::Quaternions current_quatState(Eigen::Quaternions::Identity());
+
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu(Eigen::Vector6s::Zero());
+        Eigen::Vector3s rateOfTurn(Eigen::Vector3s::Zero()); //deg/s
+
+        Scalar dt(0.001);
+        TimeStamp ts(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+
+        while( ts.get() < 1 )
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            ts.set(ts.get() + dt);
+            
+            rateOfTurn = Eigen::Vector3s::Random()*10; //to have rate of turn > 0 deg/s
+            data_imu.tail(3) = rateOfTurn* M_PI/180.0;
+            data_imu.head(3) =  current_quatState.conjugate() * (- wolf::gravity()); //gravity measured, we have no other translation movement
+
+            //compute current orientaton taking this measure into account
+            current_quatState = current_quatState * wolf::v2q(data_imu.tail(3)*dt);
+
+            //set timestamp, add bias, set data and process
+            imu_ptr->setTimeStamp(ts);
+            data_imu = data_imu + origin_bias;
+            imu_ptr->setData(data_imu);
+            sen_imu->process(imu_ptr);
+        }
+
+        expected_final_state.head(10) << 0,0,0, current_quatState.x(), current_quatState.y(), current_quatState.z(), current_quatState.w(), 0,0,0;
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION;
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 0.9999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        origin_bias << 0.0015, 0.004, -0.002, 0.005, -0.0074, -0.003;
+        t.set(0);
+        Eigen::Quaternions odom_quat(Eigen::Quaternions::Identity());
+        Eigen::Quaternions current_quatState(Eigen::Quaternions::Identity());
+
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu(Eigen::Vector6s::Zero()), data_odom3D(Eigen::Vector6s::Zero());
+        Eigen::Vector3s rateOfTurn(Eigen::Vector3s::Zero()); //deg/s
+
+        Scalar dt(0.0010), dt_odom(1.0);
+        TimeStamp ts(0.0), t_odom(0.0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+        sen_odom3D->process(mot_ptr);
+        //first odometry data will be processed at this timestamp
+        t_odom.set(t_odom.get() + dt_odom);
+
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        for(unsigned int i = 1; i<=1000; i++)
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            ts.set(i*dt);
+            
+            rateOfTurn = Eigen::Vector3s::Random()*10; //to have rate of turn > 0.99 deg/s
+            data_imu.tail<3>() = rateOfTurn* M_PI/180.0;
+            data_imu.head<3>() =  current_quatState.conjugate() * (- wolf::gravity()); //gravity measured, we have no other translation movement
+
+            //compute odometry + current orientaton taking this measure into account
+            odom_quat = odom_quat * wolf::v2q(data_imu.tail(3)*dt);
+            current_quatState = current_quatState * wolf::v2q(data_imu.tail(3)*dt);
+
+            //set timestamp, add bias, set data and process
+            imu_ptr->setTimeStamp(ts);
+            data_imu = data_imu + origin_bias;
+            imu_ptr->setData(data_imu);
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() >= t_odom.get())
+            {
+                // PROCESS ODOM 3D DATA
+                data_odom3D.head(3) << 0,0,0;
+                data_odom3D.tail(3) = q2v(odom_quat);
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement
+                odom_quat = Eigen::Quaternions::Identity(); //set to identity to have next odom relative to this last KF
+                t_odom.set(t_odom.get() + dt_odom);
+            }
+        }
+
+        expected_final_state.head(10) << 0,0,0, current_quatState.x(), current_quatState.y(), current_quatState.z(), current_quatState.w(), 0,0,0;
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot2 : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION;
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 0.4999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        origin_bias << 0.0015, 0.004, -0.002, 0.005, -0.0074, -0.003;
+        t.set(0);
+        Eigen::Quaternions odom_quat(Eigen::Quaternions::Identity());
+        Eigen::Quaternions current_quatState(Eigen::Quaternions::Identity());
+
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu(Eigen::Vector6s::Zero()), data_odom3D(Eigen::Vector6s::Zero());
+        Eigen::Vector3s rateOfTurn(Eigen::Vector3s::Zero()); //deg/s
+
+        Scalar dt(0.0010), dt_odom(0.5);
+        TimeStamp ts(0.0), t_odom(0.0);
+        int odom_count(1);
+
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+        sen_odom3D->process(mot_ptr);
+        //first odometry data will be processed at this timestamp
+        t_odom.set(odom_count*dt_odom);
+
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        for(unsigned int i = 1; i<=1000; i++)
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            ts.set(i*dt);
+            
+            rateOfTurn = Eigen::Vector3s::Random()*10; //to have rate of turn > 0.99 deg/s
+            data_imu.tail<3>() = rateOfTurn* M_PI/180.0;
+            data_imu.head<3>() =  current_quatState.conjugate() * (- wolf::gravity()); //gravity measured, we have no other translation movement
+
+            //compute odometry + current orientaton taking this measure into account
+            odom_quat = odom_quat * wolf::v2q(data_imu.tail(3)*dt);
+            current_quatState = current_quatState * wolf::v2q(data_imu.tail(3)*dt);
+
+            //set timestamp, add bias, set data and process
+            imu_ptr->setTimeStamp(ts);
+            data_imu = data_imu + origin_bias;
+            imu_ptr->setData(data_imu);
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() >= t_odom.get())
+            {
+                // PROCESS ODOM 3D DATA
+                data_odom3D.head(3) << 0,0,0;
+                data_odom3D.tail(3) = q2v(odom_quat);
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement
+                odom_quat = Eigen::Quaternions::Identity(); //set to identity to have next odom relative to this last KF
+                odom_count++;
+                t_odom.set(odom_count*dt_odom);
+            }
+        }
+
+        expected_final_state.head(10) << 0,0,0, current_quatState.x(), current_quatState.y(), current_quatState.z(), current_quatState.w(), 0,0,0;
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION;
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 0.9999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        origin_bias << 0.0015, 0.004, -0.002, 0.005, -0.0074, -0.003;
+        t.set(0);
+        Eigen::Quaternions odom_quat(Eigen::Quaternions::Identity());
+        Eigen::Quaternions current_quatState(Eigen::Quaternions::Identity());
+
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu(Eigen::Vector6s::Zero()), data_odom3D(Eigen::Vector6s::Zero());
+        Eigen::Vector3s rateOfTurn; //deg/s
+        rateOfTurn << 0,90,0;
+
+        Scalar dt(0.0010), dt_odom(1.0);
+        TimeStamp ts(0.0), t_odom(0.0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+        sen_odom3D->process(mot_ptr);
+        //first odometry data will be processed at this timestamp
+        t_odom.set(t_odom.get() + dt_odom);
+
+        data_imu.tail<3>() = rateOfTurn* M_PI/180.0; //constant rotation =
+
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+        for(unsigned int i = 1; i<=1000; i++)
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            ts.set(i*dt);
+            data_imu.head<3>() =  current_quatState.conjugate() * (- wolf::gravity()); //gravity measured, we have no other translation movement
+
+            //compute odometry + current orientaton taking this measure into account
+            odom_quat = odom_quat * wolf::v2q(data_imu.tail(3)*dt);
+            current_quatState = current_quatState * wolf::v2q(data_imu.tail(3)*dt);
+
+            //set timestamp, add bias, set data and process
+            imu_ptr->setTimeStamp(ts);
+            data_imu = data_imu + origin_bias;
+            imu_ptr->setData(data_imu);
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() >= t_odom.get())
+            {
+                // PROCESS ODOM 3D DATA
+                data_odom3D.head(3) << 0,0,0;
+                data_odom3D.tail(3) = q2v(odom_quat);
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement
+                odom_quat = Eigen::Quaternions::Identity(); //set to identity to have next odom relative to this last KF
+                t_odom.set(t_odom.get() + dt_odom);
+            }
+        }
+
+        expected_final_state.head(10) << 0,0,0, current_quatState.x(), current_quatState.y(), current_quatState.z(), current_quatState.w(), 0,0,0;
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotXY : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION;
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 0.9999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        origin_bias << 0.0015, 0.004, -0.002, 0.005, -0.0074, -0.003;
+        t.set(0);
+        Eigen::Quaternions odom_quat(Eigen::Quaternions::Identity());
+        Eigen::Quaternions current_quatState(Eigen::Quaternions::Identity());
+
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu(Eigen::Vector6s::Zero()), data_odom3D(Eigen::Vector6s::Zero());
+        Eigen::Vector3s rateOfTurn; //deg/s
+        rateOfTurn << 45,90,0;
+
+        Scalar dt(0.0010), dt_odom(1.0);
+        TimeStamp ts(0.0), t_odom(1.0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+        sen_odom3D->process(mot_ptr);
+        //first odometry data will be processed at this timestamp
+        //t_odom.set(t_odom.get() + dt_odom);
+
+        Eigen::Vector2s randomPart;
+        data_imu.tail<3>() = rateOfTurn* M_PI/180.0; //constant rotation =
+
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+        for(unsigned int i = 1; i<=500; i++)
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            ts.set(i*dt);
+
+            data_imu.head<3>() =  current_quatState.conjugate() * (- wolf::gravity()); //gravity measured, we have no other translation movement
+
+            //compute odometry + current orientaton taking this measure into account
+            odom_quat = odom_quat * wolf::v2q(data_imu.tail(3)*dt);
+            current_quatState = current_quatState * wolf::v2q(data_imu.tail(3)*dt);
+
+            //set timestamp, add bias, set data and process
+            imu_ptr->setTimeStamp(ts);
+            data_imu = data_imu + origin_bias;
+            imu_ptr->setData(data_imu);
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() >= t_odom.get())
+            {
+                // PROCESS ODOM 3D DATA
+                data_odom3D.head(3) << 0,0,0;
+                data_odom3D.tail(3) = q2v(odom_quat);
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement
+                odom_quat = Eigen::Quaternions::Identity(); //set to identity to have next odom relative to this last KF
+                t_odom.set(t_odom.get() + dt_odom);
+            }
+        }
+
+        rateOfTurn << 30,10,0;
+        data_imu.tail<3>() = rateOfTurn* M_PI/180.0;
+
+        for(unsigned int j = 1; j<=500; j++)
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            ts.set((500 + j)*dt);
+
+            /*data_imu.tail<3>() = rateOfTurn* M_PI/180.0;
+            randomPart = Eigen::Vector2s::Random(); //to have rate of turn > 0.99 deg/s
+            data_imu.segment<2>(3) += randomPart* M_PI/180.0;*/
+            data_imu.head<3>() =  current_quatState.conjugate() * (- wolf::gravity()); //gravity measured, we have no other translation movement
+
+            //compute odometry + current orientaton taking this measure into account
+            odom_quat = odom_quat * wolf::v2q(data_imu.tail(3)*dt);
+            current_quatState = current_quatState * wolf::v2q(data_imu.tail(3)*dt);
+
+            //set timestamp, add bias, set data and process
+            imu_ptr->setTimeStamp(ts);
+            data_imu = data_imu + origin_bias;
+            imu_ptr->setData(data_imu);
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() >= t_odom.get())
+            {
+                // PROCESS ODOM 3D DATA
+                data_odom3D.head(3) << 0,0,0;
+                data_odom3D.tail(3) = q2v(odom_quat);
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement
+                odom_quat = Eigen::Quaternions::Identity(); //set to identity to have next odom relative to this last KF
+                t_odom.set(t_odom.get() + dt_odom);
+            }
+        }
+
+        expected_final_state.head(10) << 0,0,0, current_quatState.x(), current_quatState.y(), current_quatState.z(), current_quatState.w(), 0,0,0;
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== INPUT FILES
+
+        char* imu_filepath;
+        char* odom_filepath;
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/imu_ComplexBiased.txt");
+        std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_Complex.txt");
+
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        odom_filepath   = new char[odom_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::strcpy(odom_filepath, odom_filepath_string.c_str());
+        std::ifstream imu_data_input;
+        std::ifstream odom_data_input;
+
+        imu_data_input.open(imu_filepath);
+        odom_data_input.open(odom_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        if(!imu_data_input.is_open() | !odom_data_input.is_open()){
+            std::cerr << "Failed to open data files... Exiting" << std::endl;
+            ADD_FAILURE();
+        }
+
+        //===================================================== END{INPUT FILES}
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1.9999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+        imu_data_input >> origin_bias[0] >> origin_bias[1] >> origin_bias[2] >> origin_bias[3] >> origin_bias[4] >> origin_bias[5];
+        imu_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                    expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+        expected_final_state.tail(6) = origin_bias;
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+
+
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+        data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+
+        Scalar input_clock;
+        TimeStamp ts(0);
+        TimeStamp t_odom(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+    
+        //read first odom data from file
+        odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+        t_odom.set(input_clock);
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        while( !imu_data_input.eof() && !odom_data_input.eof() )
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+            //std::cout << "input_clock : " << input_clock << std::endl;
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == t_odom.get()) //every 100 ms
+            {
+                // PROCESS ODOM 3D DATA
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement if there is any
+                odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+                t_odom.set(input_clock);
+            }
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //closing file
+        imu_data_input.close();
+        odom_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+    origin_KF->unfix();
+    last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex_initOK : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== INPUT FILES
+
+        char* imu_filepath;
+        char* odom_filepath;
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/imu_ComplexBiased.txt");
+        std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_Complex.txt");
+
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        odom_filepath   = new char[odom_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::strcpy(odom_filepath, odom_filepath_string.c_str());
+        std::ifstream imu_data_input;
+        std::ifstream odom_data_input;
+
+        imu_data_input.open(imu_filepath);
+        odom_data_input.open(odom_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        if(!imu_data_input.is_open() | !odom_data_input.is_open()){
+            std::cerr << "Failed to open data files... Exiting" << std::endl;
+            ADD_FAILURE();
+        }
+
+        //===================================================== END{INPUT FILES}
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1.9999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+        imu_data_input >> origin_bias[0] >> origin_bias[1] >> origin_bias[2] >> origin_bias[3] >> origin_bias[4] >> origin_bias[5];
+        imu_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                    expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;    
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+
+
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+        data_imu << -wolf::gravity(), 0,0,0;
+
+        Scalar input_clock;
+        TimeStamp ts(0);
+        TimeStamp t_odom(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+    
+        //read first odom data from file
+        odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+        t_odom.set(input_clock);
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        while( !imu_data_input.eof() && !odom_data_input.eof() )
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == t_odom.get())
+            {
+                // PROCESS ODOM 3D DATA
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement if there is any
+                odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+                t_odom.set(input_clock);
+            }
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //closing file
+        imu_data_input.close();
+        odom_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+    origin_KF->unfix();
+    last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Static_NullBiasNoisyComplex_initOK : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== INPUT FILES
+
+        char* imu_filepath;
+        char* odom_filepath;
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/imu_ComplexNoisy.txt");
+        std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_Complex.txt");
+
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        odom_filepath   = new char[odom_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::strcpy(odom_filepath, odom_filepath_string.c_str());
+        std::ifstream imu_data_input;
+        std::ifstream odom_data_input;
+
+        imu_data_input.open(imu_filepath);
+        odom_data_input.open(odom_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        if(!imu_data_input.is_open() | !odom_data_input.is_open()){
+            std::cerr << "Failed to open data files... Exiting" << std::endl;
+            ADD_FAILURE();
+        }
+
+        //===================================================== END{INPUT FILES}
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1.9999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+        imu_data_input >> origin_bias[0] >> origin_bias[1] >> origin_bias[2] >> origin_bias[3] >> origin_bias[4] >> origin_bias[5];
+        imu_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                    expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;    
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+
+
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+        data_imu << -wolf::gravity(), 0,0,0;
+
+        Scalar input_clock;
+        TimeStamp ts(0);
+        TimeStamp t_odom(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+    
+        //read first odom data from file
+        odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+        t_odom.set(input_clock);
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        while( !imu_data_input.eof() && !odom_data_input.eof() )
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == t_odom.get()) //every 100 ms
+            {
+                // PROCESS ODOM 3D DATA
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement if there is any
+                odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+                t_odom.set(input_clock);
+            }
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //closing file
+        imu_data_input.close();
+        odom_data_input.close();
+
+        //===================================================== END{PROCESS DATA}
+        origin_KF->unfix();
+        last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+class ConstraintIMU_ODOM_biasTest_Move_BiasedNoisyComplex_initOK : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs x_origin;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        //===================================================== INPUT FILES
+
+        char* imu_filepath;
+        char* odom_filepath;
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/imu_ComplexBiasedNoisy.txt");
+        std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_Complex.txt");
+
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        odom_filepath   = new char[odom_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::strcpy(odom_filepath, odom_filepath_string.c_str());
+        std::ifstream imu_data_input;
+        std::ifstream odom_data_input;
+
+        imu_data_input.open(imu_filepath);
+        odom_data_input.open(odom_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        if(!imu_data_input.is_open() | !odom_data_input.is_open()){
+            std::cerr << "Failed to open data files... Exiting" << std::endl;
+            ADD_FAILURE();
+        }
+
+        //===================================================== END{INPUT FILES}
+        
+        //===================================================== SETTING PROBLEM
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options);
+
+        // SENSOR + PROCESSOR IMU
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu_t6.yaml");
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1.99999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+    
+        //===================================================== END{SETTING PROBLEM}
+
+        //===================================================== INITIALIZATION
+
+        expected_final_state.resize(16);
+        x_origin.resize(16);
+        x_origin << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        t.set(0);
+
+        imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+        imu_data_input >> origin_bias[0] >> origin_bias[1] >> origin_bias[2] >> origin_bias[3] >> origin_bias[4] >> origin_bias[5];
+        imu_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                    expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+        expected_final_state.tail(6) = origin_bias;
+        x_origin.tail(6) = origin_bias;    
+
+        //set origin of the problem
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        //===================================================== END{INITIALIZATION}
+
+
+        //===================================================== PROCESS DATA
+        // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+        data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+
+        Scalar input_clock;
+        TimeStamp ts(0);
+        TimeStamp t_odom(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+    
+        //read first odom data from file
+        odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+        t_odom.set(input_clock);
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        while( !imu_data_input.eof() && !odom_data_input.eof() )
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == t_odom.get()) //every 100 ms
+            {
+                // PROCESS ODOM 3D DATA
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement if there is any
+                odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+                t_odom.set(input_clock);
+            }
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+        last_KF->setState(expected_final_state);
+
+        //closing file
+        imu_data_input.close();
+        odom_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+    origin_KF->unfix();
+    last_KF->unfix();
+    }
+
+    virtual void TearDown(){}
+};
+
+// tests with following conditions :
+//  var(b1,b2),        invar(p1,q1,v1,p2,q2,v2),    factor : imu(p,q,v)
+
+TEST_F(ConstraintIMU_biasTest_Static_NullBias,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getAccBiasPtr()->setState((Vector3s()<<1,2,3).finished());
+    origin_KF->getGyroBiasPtr()->setState((Vector3s()<<1,2,3).finished());
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+    last_KF->getAccBiasPtr()->setState((Vector3s()<<-1,-2,-3).finished());
+    last_KF->getGyroBiasPtr()->setState((Vector3s()<<-1,-2,-3).finished());
+
+    //wolf_problem_ptr_->print(1,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //wolf_problem_ptr_->print(1,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Static_NullBias,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    std::string report;
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Static_NonNullAccBias,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Static_NonNullAccBias,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    std::string report;
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Static_NonNullGyroBias,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Static_NonNullGyroBias,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    std::string report;
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Static_NonNullBias,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    std::string report;
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport;
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NullBias,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NullBias,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBias,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+   // wolf_problem_ptr_->print(4,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBias,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1); // 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBiasRotCst,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBiasRotCst,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBiasRotAndVCst,VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBiasRotAndVCst,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    }
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBiasRotAndVCst, VarB1B2V1P2V2_InvarP1Q1Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_biasTest_Move_NonNullBiasRot, VarB1B2V1P2V2_InvarP1Q1Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*1000)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*1000)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2V2_InvarP1Q1V1P2Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+//jacobian matrix rank deficient here - estimating both initial and final velocity
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2V1V2_InvarP1Q1P2Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    //ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+}
+
+//jacobian matrix rank deficient here - estimating both initial and final velocity
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2V1Q2V2_InvarP1Q1P2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+}
+
+//jacobian matrix rank deficient here - estimating both initial and final velocity
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2V1P2V2_InvarP1Q1Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+}
+
+//jacobian matrix rank deficient here - estimating both initial and final velocity
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2V1P2Q2V2_InvarP1Q1_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.0001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*10000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.0001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*10000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.0001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarB1B2P2Q2V2_InvarP1Q1V1_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotY, VarQ1B1B2P2Q2_InvarP1V1V2_initOK)
+{
+    //Add fix constraint on yaw to make the problem observable
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFix_cov(5,5) = 0.1;
+    CaptureBasePtr capfix = origin_KF->addCapture(std::make_shared<CaptureMotion>(0, nullptr, (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), 7, 7, 6, 0));
+    FeatureBasePtr ffix = capfix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(ffix->addConstraint(std::make_shared<ConstraintFix3D>(ffix)));
+    
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+    
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRotXY, VarQ1B1B2P2Q2_InvarP1V1V2_initOK)
+{
+    //Add fix constraint on yaw to make the problem observable
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFix_cov(5,5) = 0.1;
+    CaptureBasePtr capfix = origin_KF->addCapture(std::make_shared<CaptureMotion>(0, nullptr, (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), 7, 7, 6, 0));
+    FeatureBasePtr ffix = capfix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(ffix->addConstraint(std::make_shared<ConstraintFix3D>(ffix)));
+    
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+    
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*1000)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*1000)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2V2_InvarP1Q1V1P2Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2V1V2_InvarP1Q1P2Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2V1Q2V2_InvarP1Q1P2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2V1P2V2_InvarP1Q1Q2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2V1P2Q2V2_InvarP1Q1_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.0001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*10000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.0001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*10000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.0001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarB1B2P2Q2V2_InvarP1Q1V1_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbation of origin bias
+    Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.00001);
+    Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+    origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+    origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*1000)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.00001)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+//not constrained enough, thus, estimation fails
+/*TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasRot, VarAll_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->unfix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->setState(expected_final_state);
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    ASSERT_MATRIX_APPROX(origin_KF->getPPtr()->getState(), x_origin.head(3), wolf::Constants::EPS*100)
+    Eigen::Map<const Eigen::Quaternions> estimatedOriginQuat(origin_KF->getOPtr()->getState().data()), expectedOriginQuat(x_origin.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedOriginQuat, expectedOriginQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*100)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}*/
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex_initOK, VarB1B2_InvarP1Q1V1P2Q2V2)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    WOLF_WARN("Precision set to ", 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex_initOK, VarB1B2P2Q2_InvarP1Q1V1V2)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    WOLF_WARN("Precision set to ", 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.001) //biased + noisy imu, consider an error of 1mm
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, 0.00001)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex_initOK, VarB1B2P2Q2V2_InvarP1Q1V1)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    WOLF_WARN("Precision set to ", 0.0001)
+
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.0001)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), 0.0001)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex_initOK, VarAll)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->unfix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->unfix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    WOLF_WARN("Precision set to ", 0.001)
+
+    ASSERT_MATRIX_APPROX(origin_KF->getVPtr()->getState(), x_origin.segment(7,3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getPPtr()->getState(), x_origin.head(3), 0.0001)
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.0001)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.0001)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.0001)
+}
+
+//Commented tests below are falling in local minimum
+/*
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex, VarB1B2_InvarP1Q1V1P2Q2V2_initZero) //Falling in local minimum
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    //ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    
+    //ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    //ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex, VarB1B2P2Q2V2_InvarP1Q1V1_initZero) //Falling in local minimum
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), wolf::Constants::EPS*100)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+}
+*/
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex, VarB1B2_InvarP1Q1V1P2Q2V2_initOK)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+
+    /*ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)
+    
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), wolf::Constants::EPS*100)*/
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_NonNullBiasComplex_initOK,VarB1B2_InvarP1Q1V1P2Q2V2_ErrBias)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    wolf::Scalar epsilon_bias = 0.0000001;
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-6")
+    epsilon_bias = 0.000001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    WOLF_WARN("Precision set to ", 0.001)
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-4")
+    epsilon_bias = 0.0001;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-2")
+    epsilon_bias = 0.01;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+    //Only biases are unfixed
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+    //==============================================================
+    //WOLF_INFO("Starting error bias 1e-1")
+    epsilon_bias = 0.1;
+
+    for(int i = 1; i<10; i++)
+    {
+        err = Eigen::Vector6s::Random() * epsilon_bias*10;
+        perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(expected_final_state);
+
+        report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+
+        //Only biases are unfixed
+        ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+        ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+
+        ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.001)
+        ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.001)
+    }
+}
+
+//Tests related to noise
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Static_NullBiasNoisyComplex_initOK, varB1B2P2Q2B2_invarP1Q1V1V2)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << report << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.005)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Static_NullBiasNoisyComplex_initOK, varQ1B1P2Q2B2_invarP1V1V2) // added a Fix3D constraint on 1st KF
+{
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFix_cov(5,5) = 0.1;
+    CaptureBasePtr capfix = origin_KF->addCapture(std::make_shared<CaptureMotion>(0, nullptr, (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), 7, 7, 6, 0));
+    FeatureBasePtr ffix = capfix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(ffix->addConstraint(std::make_shared<ConstraintFix3D>(ffix)));
+
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << report << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.005)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Static_NullBiasNoisyComplex_initOK, varB1B2_invarP1Q1V1P2Q2V2)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getAccBiasPtr()->unfix();
+    origin_KF->getGyroBiasPtr()->unfix();
+
+    last_KF->getPPtr()->fix();
+    last_KF->getOPtr()->fix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << report << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.01)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.01)
+
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.01)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.01)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_BiasedNoisyComplex_initOK, varB1P2Q2V2B2_invarP1Q1V1)
+{
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->unfix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << report << std::endl;
+
+    //These ASSERTS can be removed since we are more interested in using covariances to make sure that expected values are inside estimated +/- 2*std
+    WOLF_WARN("Precision set to ", 0.01)
+
+    ASSERT_MATRIX_APPROX(origin_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.01)
+    ASSERT_MATRIX_APPROX(origin_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.01)
+
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.0001)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, wolf::Constants::EPS*100)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), 0.01)
+    ASSERT_MATRIX_APPROX(last_KF->getAccBiasPtr()->getState(), origin_bias.head(3), 0.01)
+    ASSERT_MATRIX_APPROX(last_KF->getGyroBiasPtr()->getState(), origin_bias.tail(3), 0.01)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+TEST_F(ConstraintIMU_ODOM_biasTest_Move_BiasedNoisyComplex_initOK, varQ1B1P2Q2B2_invarP1V1V2) // added a Fix3D constraint on 1st KF
+{
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFix_cov(5,5) = 0.1;
+    CaptureBasePtr capfix = origin_KF->addCapture(std::make_shared<CaptureMotion>(0, nullptr, (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), 7, 7, 6, 0));
+    FeatureBasePtr ffix = capfix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(ffix->addConstraint(std::make_shared<ConstraintFix3D>(ffix)));
+
+    //prepare problem for solving
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->fix();
+
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //perturbatte a little the bias of origin state
+    Eigen::VectorXs perturbated_origin_state(x_origin);
+    wolf::Scalar epsilon_bias = 0.0001;
+    Eigen::Vector6s err;
+
+    err = Eigen::Vector6s::Random() * epsilon_bias*10;
+    perturbated_origin_state.tail(6) = x_origin.tail(6) + err;
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(expected_final_state);
+
+    std::string report = ceres_manager_wolf_diff->solve(1);// 0: nothing, 1: BriefReport, 2: FullReport
+    ceres_manager_wolf_diff->computeCovariances(ALL);
+    std::cout << report << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_MATRIX_APPROX(last_KF->getPPtr()->getState(), expected_final_state.head(3), 0.005)
+    Eigen::Map<const Eigen::Quaternions> estimatedLastQuat(last_KF->getOPtr()->getState().data()), expectedLastQuat(expected_final_state.segment(3,4).data());
+    ASSERT_QUATERNION_APPROX(estimatedLastQuat, expectedLastQuat, 0.001)
+    ASSERT_MATRIX_APPROX(last_KF->getVPtr()->getState(), expected_final_state.segment(7,3), wolf::Constants::EPS*1000)
+
+    Eigen::Matrix<wolf::Scalar, 16, 1> cov_stdev, actual_state(last_KF->getState());
+    Eigen::MatrixXs covX(16,16);
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero()), cov4(Eigen::Matrix4s::Zero());
+        
+    //get data from covariance blocks
+    wolf_problem_ptr_->getFrameCovariance(last_KF, covX);
+
+    for(int i = 0; i<16; i++)
+        cov_stdev(i) = ( covX(i,i)? 2*sqrt(covX(i,i)):0); //if diagonal value is 0 then store 0 else store 2*sqrt(diag_value)
+    
+    /*TEST_COUT << "2*std : " << cov_stdev.transpose();
+    TEST_COUT << "expect : " << expected_final_state.transpose(); //expected final state
+    TEST_COUT << "estim : " << last_KF->getState().transpose(); //estimated final state*/
+
+    for(unsigned int i = 0; i<16; i++)
+        assert((expected_final_state(i) <= actual_state(i) + cov_stdev(i)) && (expected_final_state(i) >= actual_state(i) - cov_stdev(i)));
+
+    if(cov_stdev.tail(6).maxCoeff()>=1)
+        WOLF_WARN("Big 2*stdev on one or more biases! Max coeff :", cov_stdev.tail(6).maxCoeff())
+}
+
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  ::testing::GTEST_FLAG(filter) = "ConstraintIMU_biasTest_Move_NonNullBiasRot.*";
+  return RUN_ALL_TESTS();
+}
diff --git a/src/test/gtest_constraint_odom_3D.cpp b/src/test/gtest_constraint_odom_3D.cpp
index 1dea78dc865e10d3da688655af0908538aab6e0b..077568e260e28f83d9aabdc1e16699de827252d1 100644
--- a/src/test/gtest_constraint_odom_3D.cpp
+++ b/src/test/gtest_constraint_odom_3D.cpp
@@ -43,9 +43,9 @@ FrameBasePtr frm0 = problem->emplaceFrame(KEY_FRAME, problem->zeroState(), TimeS
 FrameBasePtr frm1 = problem->emplaceFrame(KEY_FRAME, delta, TimeStamp(1));
 
 // Capture, feature and constraint from frm1 to frm0
-CaptureBasePtr cap1 = frm1->addCapture(std::make_shared<CaptureMotion>(1, nullptr, delta, 7, 6));
+CaptureBasePtr cap1 = frm1->addCapture(std::make_shared<CaptureMotion>(1, nullptr, delta, 7, 7, 6, 0));
 FeatureBasePtr fea1 = cap1->addFeature(std::make_shared<FeatureBase>("ODOM 3D", delta, data_cov));
-ConstraintOdom3DPtr ctr1 = std::static_pointer_cast<ConstraintOdom3D>(fea1->addConstraint(std::make_shared<ConstraintOdom3D>(fea1, frm0))); // create and add
+ConstraintOdom3DPtr ctr1 = std::static_pointer_cast<ConstraintOdom3D>(fea1->addConstraint(std::make_shared<ConstraintOdom3D>(fea1, frm0, nullptr))); // create and add
 ConstraintBasePtr dummy = frm0->addConstrainedBy(ctr1);
 
 ////////////////////////////////////////////////////////
@@ -93,4 +93,3 @@ int main(int argc, char **argv)
   testing::InitGoogleTest(&argc, argv);
   return RUN_ALL_TESTS();
 }
-
diff --git a/src/test/gtest_feature_imu.cpp b/src/test/gtest_feature_imu.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a5f57c9a0b1b16409666fea0bdd539369954fc53
--- /dev/null
+++ b/src/test/gtest_feature_imu.cpp
@@ -0,0 +1,161 @@
+//Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "sensor_imu.h"
+#include "capture_imu.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu.h"
+
+#include "utils_gtest.h"
+#include "../src/logging.h"
+
+class FeatureIMU_test : public testing::Test
+{
+
+    public: //These can be accessed in fixtures
+        wolf::ProblemPtr wolf_problem_ptr_;
+        wolf::TimeStamp ts;
+        wolf::CaptureIMUPtr imu_ptr;
+        Eigen::VectorXs state_vec;
+        Eigen::VectorXs delta_preint;
+        Eigen::Matrix<wolf::Scalar,9,9> delta_preint_cov;
+        std::shared_ptr<wolf::FeatureIMU> feat_imu;
+        wolf::FrameIMUPtr last_frame;
+        wolf::FrameBasePtr origin_frame;
+        Eigen::MatrixXs dD_db_jacobians;
+        wolf::ProcessorBasePtr processor_ptr_;
+
+    //a new of this will be created for each new test
+    virtual void SetUp()
+    {
+        using namespace wolf;
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        // Wolf problem
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs IMU_extrinsics(7);
+        IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot
+        IntrinsicsIMUPtr sen_imu_params = std::make_shared<IntrinsicsIMU>();
+        SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, sen_imu_params);
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", "");
+
+    // Time and data variables
+        TimeStamp t;
+        Eigen::Vector6s data_;
+
+        t.set(0);
+
+    // Set the origin
+        Eigen::VectorXs x0(16);
+        x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+        origin_frame = wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(x0, t);  //create a keyframe at origin
+    
+    // Create one capture to store the IMU data arriving from (sensor / callback / file / etc.)
+    // give the capture a big covariance, otherwise it will be so small that it won't pass following assertions
+        imu_ptr = std::make_shared<CaptureIMU>(t, sensor_ptr, data_, Eigen::Matrix6s::Identity()); 
+        imu_ptr->setFramePtr(origin_frame); //to get ptr to Frm ni processorIMU and then get biases
+
+    //process data
+        data_ << 2, 0, 9.8, 0, 0, 0;
+        t.set(0.1);
+        // Expected state after one integration
+        //x << 0.01,0,0, 0,0,0,1, 0.2,0,0, 0,0,0, 0,0,0; // advanced at a=2m/s2 during 0.1s ==> dx = 0.5*2*0.1^2 = 0.01; dvx = 2*0.1 = 0.2
+    // assign data to capture
+        imu_ptr->setData(data_);
+        imu_ptr->setTimeStamp(t);
+    // process data in capture
+        sensor_ptr->process(imu_ptr);
+
+    //create FrameIMU
+        ts = wolf_problem_ptr_->getProcessorMotionPtr()->getBuffer().get().back().ts_;
+        state_vec = wolf_problem_ptr_->getProcessorMotionPtr()->getCurrentState();
+   	    last_frame = std::make_shared<FrameIMU>(KEY_FRAME, ts, state_vec);
+        wolf_problem_ptr_->getTrajectoryPtr()->addFrame(last_frame);
+        
+    //create a feature
+        delta_preint = wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_;
+        delta_preint_cov = wolf_problem_ptr_->getProcessorMotionPtr()->getMotion().delta_integr_cov_;
+        //feat_imu = std::make_shared<FeatureIMU>(delta_preint, delta_preint_cov);
+        std::static_pointer_cast<wolf::ProcessorIMU>(wolf_problem_ptr_->getProcessorMotionPtr())->getJacobianCalib(dD_db_jacobians);
+        feat_imu = std::make_shared<FeatureIMU>(delta_preint, delta_preint_cov, imu_ptr, dD_db_jacobians);
+        feat_imu->setCapturePtr(imu_ptr); //associate the feature to a capture
+
+    }
+
+    virtual void TearDown()
+    {
+        // code here will be called just after the test completes
+        // ok to through exceptions from here if need be
+        /*
+            You can do deallocation of resources in TearDown or the destructor routine. 
+                However, if you want exception handling you must do it only in the TearDown code because throwing an exception 
+                from the destructor results in undefined behavior.
+            The Google assertion macros may throw exceptions in platforms where they are enabled in future releases. 
+                Therefore, it's a good idea to use assertion macros in the TearDown code for better maintenance.
+        */
+    }
+};
+
+TEST_F(FeatureIMU_test, check_frame)
+{
+    // set variables
+    using namespace wolf;
+
+    FrameBasePtr left_frame = feat_imu->getFramePtr();
+    wolf::TimeStamp t;
+    left_frame->getTimeStamp(t);
+    origin_frame->getTimeStamp(ts);
+
+    ASSERT_EQ(t,ts) << "t != ts \t t=" << t << "\t ts=" << ts << std::endl;
+    ASSERT_TRUE(origin_frame->isKey());
+    ASSERT_TRUE(left_frame->isKey());
+
+    wolf::StateBlockPtr origin_pptr, origin_optr, origin_vptr, left_pptr, left_optr, left_vptr;
+    origin_pptr = origin_frame->getPPtr();
+    origin_optr = origin_frame->getOPtr();
+    origin_vptr = origin_frame->getVPtr();
+    left_pptr = left_frame->getPPtr();
+    left_optr = left_frame->getOPtr();
+    left_vptr = left_frame->getVPtr();
+
+    ASSERT_MATRIX_APPROX(origin_pptr->getState(), left_pptr->getState(), wolf::Constants::EPS_SMALL);
+    Eigen::Map<const Eigen::Quaternions> origin_Quat(origin_optr->getState().data()), left_Quat(left_optr->getState().data());
+    ASSERT_QUATERNION_APPROX(origin_Quat, left_Quat, wolf::Constants::EPS_SMALL);
+    ASSERT_MATRIX_APPROX(origin_vptr->getState(), left_vptr->getState(), wolf::Constants::EPS_SMALL);
+
+    ASSERT_EQ(origin_frame->id(), left_frame->id());
+}
+
+TEST_F(FeatureIMU_test, access_members)
+{
+    using namespace wolf;
+
+    Eigen::VectorXs delta(10);
+    //dx = 0.5*2*0.1^2 = 0.01; dvx = 2*0.1 = 0.2; dz = 0.5*9.8*0.1^2 = 0.049; dvz = 9.8*0.1 = 0.98
+    delta << 0.01,0,0.049, 0,0,0,1, 0.2,0,0.98;
+    ASSERT_MATRIX_APPROX(feat_imu->dp_preint_, delta.head<3>(), wolf::Constants::EPS_SMALL);
+    ASSERT_MATRIX_APPROX(feat_imu->dv_preint_, delta.tail<3>(), wolf::Constants::EPS);
+    EXPECT_MATRIX_APPROX(feat_imu->dv_preint_, delta.tail<3>(), wolf::Constants::EPS_SMALL*10)
+
+    Eigen::Map<const Eigen::Quaternions> delta_quat(delta.segment<4>(3).data());
+    ASSERT_QUATERNION_APPROX(feat_imu->dq_preint_, delta_quat, wolf::Constants::EPS_SMALL);
+}
+
+TEST_F(FeatureIMU_test, addConstraint)
+{
+    using namespace wolf;
+    
+    FrameIMUPtr frm_imu = std::static_pointer_cast<FrameIMU>(last_frame);
+    ConstraintIMUPtr constraint_imu = std::make_shared<ConstraintIMU>(feat_imu, std::static_pointer_cast<FrameIMU>(frm_imu), processor_ptr_);
+    feat_imu->addConstraint(constraint_imu);
+    origin_frame->addConstrainedBy(constraint_imu);
+}
+
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  return RUN_ALL_TESTS();
+}
diff --git a/src/test/gtest_frame_base.cpp b/src/test/gtest_frame_base.cpp
index 06d6cb6d453fcb6be4e4f44ecc240187977f45c4..6ccc9ab0a48cb6966b8d70e22069a61cbce8805c 100644
--- a/src/test/gtest_frame_base.cpp
+++ b/src/test/gtest_frame_base.cpp
@@ -12,6 +12,7 @@
 
 #include "../frame_base.h"
 #include "../sensor_odom_2D.h"
+#include "../processor_odom_2D.h"
 #include "../constraint_odom_2D.h"
 #include "../capture_motion.h"
 
@@ -73,11 +74,13 @@ TEST(FrameBase, LinksToTree)
     T->addFrame(F1);
     FrameBasePtr F2 = make_shared<FrameBase>(1, make_shared<StateBlock>(2), make_shared<StateBlock>(1));
     T->addFrame(F2);
-    CaptureMotionPtr C = make_shared<CaptureMotion>(1, S, Vector3s::Zero(), 3, 3);
+    CaptureMotionPtr C = make_shared<CaptureMotion>(1, S, Vector3s::Zero(), 3, 3, 3, 0);
     F1->addCapture(C);
+    /// @todo link sensor & proccessor
+    ProcessorBasePtr p = std::make_shared<ProcessorOdom2D>();
     FeatureBasePtr f = make_shared<FeatureBase>("f", Vector1s(1), Matrix<Scalar,1,1>::Identity()*.01);
     C->addFeature(f);
-    ConstraintOdom2DPtr c = make_shared<ConstraintOdom2D>(f, F2);
+    ConstraintOdom2DPtr c = make_shared<ConstraintOdom2D>(f, F2, p);
     f->addConstraint(c);
 
     // c-by link F2 -> c not yet established
diff --git a/src/test/gtest_frame_imu.cpp b/src/test/gtest_frame_imu.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..80c84341c7242fdccef7630c9aadea9fe155cff0
--- /dev/null
+++ b/src/test/gtest_frame_imu.cpp
@@ -0,0 +1,39 @@
+/*
+ * gtest_frame_imu.cpp
+ *
+ *  Created on: Jan 05, 2017
+ *      Author: Dinesh Atchuthan
+ */
+
+ #include "utils_gtest.h"
+#include "../logging.h"
+
+#include "../frame_imu.h"
+#include "../capture_motion.h"
+
+#include <iostream>
+
+using namespace Eigen;
+using namespace std;
+using namespace wolf;
+
+TEST(FrameIMU, Getters)
+{
+    TimeStamp ts(0.1);
+    Eigen::VectorXs state0(16);
+    state0 << 0,0,0,  0,0,0,  0,0,0,1,  0,0,.001,  0,0,.002;
+    FrameIMUPtr F = make_shared<FrameIMU>(KEY_FRAME, ts, state0);
+
+    Eigen::Vector3s acc_b = F->getAccBiasPtr()->getState();
+    Eigen::Vector3s gyro_b = F->getGyroBiasPtr()->getState();
+
+    ASSERT_TRUE((state0.segment(10,3) - acc_b).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL));
+    ASSERT_TRUE((state0.tail(3) - gyro_b).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL));
+}
+
+
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  return RUN_ALL_TESTS();
+}
diff --git a/src/test/gtest_imuBias.cpp b/src/test/gtest_imuBias.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b540fe0eb083f9485fd7a74bf8b0ab4c39b7580b
--- /dev/null
+++ b/src/test/gtest_imuBias.cpp
@@ -0,0 +1,499 @@
+/**
+ * \file gtest_imuBias.cpp
+ *
+ *  Created on: May 15, 2017
+ *      \author: Dinsh Atchuthan
+ */
+
+//Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "feature_fix.h"
+#include "constraint_fix_3D.h"
+#include "constraint_fix_bias.h"
+#include "sensor_imu.h"
+#include "capture_imu.h"
+#include "capture_fix.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu.h"
+#include "processor_odom_3D.h"
+#include "ceres_wrapper/ceres_manager.h"
+
+#include "utils_gtest.h"
+#include "../src/logging.h"
+
+#include <iostream>
+#include <fstream>
+
+//#define OUTPUT_DATA
+
+using namespace Eigen;
+using namespace std;
+using namespace wolf;
+
+
+// ProcessorIMU_Real_CaptureFix is similar to ProcessorIMU_Real_CaptureFix_odom
+// the difference is that the second one gets the odometry measurements from a file while the first one imposes only one odometry
+// between first and last KF
+class ProcessorIMU_Real_CaptureFix : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        wolf::Scalar dt;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs expected_origin_state;
+        std::ofstream debug_results;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        //===================================================== SETTING PROBLEM
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+
+        // SENSOR + PROCESSOR IMU
+        //We want a processorIMU with a specific max_time_span (1s) forour test
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+        prc_imu_params->max_time_span = 10;
+        prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_imu_params->dist_traveled = 1000000000;
+        prc_imu_params->angle_turned = 1000000000;
+
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1.99999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+    //===================================================== END{SETTING PROBLEM}
+
+        char* imu_filepath;
+        //std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/M1.txt");
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/bias_plateformRotateX.txt");
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::ifstream imu_data_input;
+
+        imu_data_input.open(imu_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        ASSERT_TRUE(imu_data_input.is_open()) << "Failed to open data files... Exiting";
+
+        #ifdef OUTPUT_DATA
+        //std::ofstream debug_results;
+        debug_results.open("KFO_cfix3D.dat");
+        #endif
+
+        //===================================================== SETTING PROBLEM
+
+        // reset origin of problem
+        Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+        t.set(0);
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+        data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+        data_odom3D << 0,-0.06,0, 0,0,0;
+        expected_final_state.resize(16);
+        expected_final_state << 0,-0.06,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+        expected_origin_state.resize(16);
+        expected_origin_state << 0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0;
+
+        Scalar input_clock;
+        TimeStamp ts(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+
+        // process all IMu data and then finish with the odom measurement that will create a new constraint
+
+        while( !imu_data_input.eof())
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+        }
+
+        // PROCESS ODOM 3D DATA
+        mot_ptr->setTimeStamp(ts);
+        mot_ptr->setData(data_odom3D);
+        sen_odom3D->process(mot_ptr);
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+        //closing file
+        imu_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+    }
+
+    virtual void TearDown(){}
+};
+
+class ProcessorIMU_Real_CaptureFix_odom : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        wolf::Scalar dt;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Vector6s origin_bias;
+        Eigen::VectorXs expected_final_state;
+        Eigen::VectorXs expected_origin_state;
+        std::ofstream debug_results;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        //===================================================== SETTING PROBLEM
+        std::string wolf_root = _WOLF_ROOT_DIR;
+
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+
+        // SENSOR + PROCESSOR IMU
+        //We want a processorIMU with a specific max_time_span (1s) forour test
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+        prc_imu_params->max_time_span = 10;
+        prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_imu_params->dist_traveled = 1000000000;
+        prc_imu_params->angle_turned = 1000000000;
+
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D_HQ.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 0.49999;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+    //===================================================== END{SETTING PROBLEM}
+
+        char* imu_filepath;
+        char * odom_filepath;
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/imu_testPatternRot.txt");  //imu_testPattern3, imu_testPattern3_biased
+        std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_testPatternRot.txt"); //odom_testPattern3_biased,
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        odom_filepath   = new char[odom_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::strcpy(odom_filepath, odom_filepath_string.c_str());
+        std::ifstream imu_data_input;
+        std::ifstream odom_data_input;
+
+        imu_data_input.open(imu_filepath);
+        odom_data_input.open(odom_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        ASSERT_TRUE(imu_data_input.is_open() && odom_data_input.is_open()) << "Failed to open data files... Exiting";
+
+        #ifdef OUTPUT_DATA
+        debug_results.open(wolf_root + "/KFO_cfix3D_odom.dat");
+        if (debug_results.is_open()) std::cout << "debug results file opened!" << wolf_root + "KFO_cfix3D_odom.dat" << std::endl;
+        else std::cout << "debug results file open failed!" << wolf_root + "KFO_cfix3D_odom.dat" << std::endl;
+        #endif
+
+        //===================================================== SETTING PROBLEM
+
+        // reset origin of problem
+        Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+        t.set(0);
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+
+        expected_final_state.resize(16);
+        expected_origin_state.resize(16);
+
+        imu_data_input >> expected_origin_state[0] >> expected_origin_state[1] >> expected_origin_state[2] >> expected_origin_state[6] >> expected_origin_state[3] >> expected_origin_state[4] >> expected_origin_state[5] >> expected_origin_state[7] >> expected_origin_state[8] >> expected_origin_state[9];
+        imu_data_input >> origin_bias[0] >> origin_bias[1] >> origin_bias[2] >> origin_bias[3] >> origin_bias[4] >> origin_bias[5];
+        imu_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                    expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+        expected_final_state.tail(6) = origin_bias;
+        expected_origin_state.tail(6) = origin_bias;  
+
+        wolf::Scalar input_clock;
+        TimeStamp ts(0);
+        TimeStamp t_odom(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 7, 6, 0);
+
+        // process all IMu data and then finish with the odom measurement that will create a new constraint
+        //read first odom data from file
+        odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+        t_odom.set(input_clock);
+
+        while( !imu_data_input.eof())
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            //imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == t_odom.get())
+            {
+                WOLF_DEBUG("ts : ", ts.get())
+                // PROCESS ODOM 3D DATA
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement if there is any
+                odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+                t_odom.set(input_clock);
+            }
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+        //closing files
+        imu_data_input.close();
+        odom_data_input.close();
+    }
+
+    virtual void TearDown(){}
+};
+
+TEST_F(ProcessorIMU_Real_CaptureFix_odom,M1_VarQ1B1P2Q2B2_InvarP1V1V2_initOK_ConstrO_KF0_cfixem6To100)
+{
+    // Create a ConstraintFix that will constraint the initial pose
+    // give it a big small covariance on yaw and big on the other parts of the diagonal.
+    // This is needed to make the problem observable, otherwise the jacobian would be rank deficient -> cannot compute covariances
+
+    expected_origin_state.tail(6) << 0,0,0, 0,0,0;
+
+    Eigen::MatrixXs featureFix_cov(6,6);
+    featureFix_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFix_cov(5,5) = 0.1;
+    CaptureBasePtr capfix = origin_KF->addCapture(std::make_shared<CaptureMotion>(0, nullptr, (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), 7, 7, 6, 0));
+    FeatureBasePtr ffix = capfix->addFeature(std::make_shared<FeatureBase>("ODOM 3D", (Eigen::Vector7s() << 0,0,0, 0,0,0,1).finished(), featureFix_cov));
+    ConstraintFix3DPtr ctr_fix = std::static_pointer_cast<ConstraintFix3D>(ffix->addConstraint(std::make_shared<ConstraintFix3D>(ffix)));
+
+    // Create a ConstraintFixBias for origin KeyFrame
+    Eigen::MatrixXs featureFixBias_cov(6,6);
+    featureFixBias_cov = Eigen::MatrixXs::Identity(6,6); 
+    featureFixBias_cov.topLeftCorner(3,3) *= 0.0007;        // sqrt(0.0007) = 0.0265 m/s2
+    featureFixBias_cov.bottomRightCorner(3,3) *= 0.0007;  // sart(0.0007) = 0.005 rad/s
+    CaptureBasePtr capfixbias = origin_KF->addCapture(std::make_shared<CaptureMotion>(0, nullptr, (Eigen::Vector6s() << 0,0,0, 0,0,0).finished(), featureFixBias_cov, 6, 7, 6, 0));
+    //create a FeatureBase to constraint biases
+    FeatureBasePtr ffixbias = capfixbias->addFeature(std::make_shared<FeatureBase>("FIX BIAS", (Eigen::Vector6s() << 0,0,0, 0,0,0).finished(), featureFixBias_cov));
+    ConstraintFixBiasPtr ctr_fixBias = std::static_pointer_cast<ConstraintFixBias>(ffixbias->addConstraint(std::make_shared<ConstraintFixBias>(ffixbias)));
+
+    //unfix / fix stateblocks
+    origin_KF->getPPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getAccBiasPtr()->unfix();
+    last_KF->getPPtr()->unfix();
+    last_KF->getOPtr()->unfix();
+    last_KF->getVPtr()->fix();
+
+    //last_KF->setState(expected_final_state);
+    FrameBaseList frameList = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList();
+
+    //Fix velocity to [0 0 0] in all frames
+    for(auto frame : frameList)
+    {
+        frame->getVPtr()->setState((Eigen::Vector3s()<<0,0,0).finished());
+        frame->getVPtr()->fix();
+    }
+
+    //vary the covariance in odometry position displacement + solve + output result
+    for (wolf::Scalar p_var = 0.000001; p_var <= 0.04; p_var=p_var*10)
+//        for (wolf::Scalar p_var = 0.0001; p_var <= 0.0001; p_var=p_var*10)
+    {
+        for(auto frame : frameList)
+        {
+            ConstraintBaseList ctr_list = frame->getConstrainedByList();
+            //std::cout << "ctr_list size : " << ctr_list.size() << std::endl;
+
+            for(auto ctr : ctr_list)
+            {
+                //std::cout << "ctr ID : " << (*ctr_it)->getTypeId() << std::endl;
+                if (ctr->getTypeId() == CTR_ODOM_3D) //change covariances in features to constraint only position
+                {
+                    Eigen::MatrixXs meas_cov(ctr->getMeasurementCovariance());
+                    meas_cov.topLeftCorner(3,3) = (Eigen::Matrix3s() << p_var, 0, 0, 0, p_var, 0, 0, 0, p_var).finished();
+                    ctr->getFeaturePtr()->setMeasurementCovariance(meas_cov);
+                }
+            }
+        }
+
+        //reset origin to its initial value (value it had before solving any problem) for the new solve + perturbate
+        Eigen::Vector3s random_err(Eigen::Vector3s::Random() * 0.0001);
+        origin_KF->setState(expected_origin_state);
+        Eigen::Vector3s accBias = origin_KF->getAccBiasPtr()->getState();
+        Eigen::Vector3s gyroBias = origin_KF->getGyroBiasPtr()->getState();
+        origin_KF->getAccBiasPtr()->setState(accBias + random_err);
+        origin_KF->getGyroBiasPtr()->setState(gyroBias + random_err);
+        
+        wolf_problem_ptr_->print(4,0,1,0);
+
+        //solve + compute covariance
+        ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+        ceres_manager_wolf_diff->computeCovariances(ALL);
+
+        wolf_problem_ptr_->print(4,0,1,0);
+
+        //format output : get states + associated covariances
+        Eigen::MatrixXs cov_AB1(3,3), cov_GB1(3,3), cov_P1(3,3);
+        Eigen::MatrixXs cov_Q1(4,4);
+        wolf_problem_ptr_->getCovarianceBlock(origin_KF->getAccBiasPtr(), origin_KF->getAccBiasPtr(), cov_AB1);
+        wolf_problem_ptr_->getCovarianceBlock(origin_KF->getGyroBiasPtr(), origin_KF->getGyroBiasPtr(), cov_GB1);
+        wolf_problem_ptr_->getCovarianceBlock(origin_KF->getPPtr(), origin_KF->getPPtr(), cov_P1);
+        wolf_problem_ptr_->getCovarianceBlock(origin_KF->getOPtr(), origin_KF->getOPtr(), cov_Q1);
+
+        Eigen::MatrixXs cov_AB2(3,3), cov_GB2(3,3), cov_P2(3,3);
+        Eigen::MatrixXs cov_Q2(4,4);
+        wolf_problem_ptr_->getCovarianceBlock(last_KF->getAccBiasPtr(), last_KF->getAccBiasPtr(), cov_AB2);
+        wolf_problem_ptr_->getCovarianceBlock(last_KF->getGyroBiasPtr(), last_KF->getGyroBiasPtr(), cov_GB2);
+        wolf_problem_ptr_->getCovarianceBlock(last_KF->getPPtr(), last_KF->getPPtr(), cov_P2);
+        wolf_problem_ptr_->getCovarianceBlock(last_KF->getOPtr(), last_KF->getOPtr(), cov_Q2);
+        std::cout << p_var << "\n\tcov_AB1 : " << sqrt(cov_AB1(0,0)) << ", " << sqrt(cov_AB1(1,1)) << ", " << sqrt(cov_AB1(2,2))
+                << "\n\t cov_GB1 : " << sqrt(cov_GB1(0,0)) << ", " << sqrt(cov_GB1(1,1)) << ", " << sqrt(cov_GB1(2,2))
+                << "\n\t cov_P2 : " << sqrt(cov_P2(0,0)) << ", " << sqrt(cov_P2(1,1)) << ", " << sqrt(cov_P2(2,2)) << std::endl;
+
+        #ifdef OUTPUT_DATA
+
+        debug_results << sqrt(p_var) << "\t" << origin_KF->getPPtr()->getState().transpose() << "\t" << origin_KF->getOPtr()->getState().transpose() << "\t" << origin_KF->getAccBiasPtr()->getState().transpose() << "\t" << origin_KF->getGyroBiasPtr()->getState().transpose() << "\t"
+                    << sqrt(cov_P1(0,0)) << "\t" << sqrt(cov_P1(1,1)) << "\t" << sqrt(cov_P1(2,2)) << "\t" 
+                    << sqrt(cov_Q1(0,0)) << "\t" << sqrt(cov_Q1(1,1)) << "\t" << sqrt(cov_Q1(2,2)) << "\t" 
+                    << sqrt(cov_AB1(0,0)) << "\t" << sqrt(cov_AB1(1,1)) << "\t" << sqrt(cov_AB1(2,2)) << "\t" 
+                    << sqrt(cov_GB1(0,0)) << "\t" << sqrt(cov_GB1(1,1)) << "\t" << sqrt(cov_GB1(2,2)) << "\t"
+                    << last_KF->getPPtr()->getState().transpose() << "\t" << last_KF->getOPtr()->getState().transpose() << "\t" << last_KF->getAccBiasPtr()->getState().transpose() << "\t" << last_KF->getGyroBiasPtr()->getState().transpose() << "\t"
+                    << sqrt(cov_P2(0,0)) << "\t" << sqrt(cov_P2(1,1)) << "\t" << sqrt(cov_P2(2,2)) << "\t" 
+                    << sqrt(cov_Q2(0,0)) << "\t" << sqrt(cov_Q2(1,1)) << "\t" << sqrt(cov_Q2(2,2)) << "\t" 
+                    << sqrt(cov_AB2(0,0)) << "\t" << sqrt(cov_AB2(1,1)) << "\t" << sqrt(cov_AB2(2,2)) << "\t" 
+                    << sqrt(cov_GB2(0,0)) << "\t" << sqrt(cov_GB2(1,1)) << "\t" << sqrt(cov_GB2(2,2)) << std::endl;
+
+        /*debug_results << sqrt(p_var) << "\t" << last_KF->getPPtr()->getState().transpose() << "\t" << last_KF->getOPtr()->getState().transpose() << "\t" << last_KF->getAccBiasPtr()->getState().transpose() << "\t" << last_KF->getGyroBiasPtr()->getState().transpose() << "\t"
+                    << sqrt(cov_P2(0,0)) << "\t" << sqrt(cov_P2(1,1)) << "\t" << sqrt(cov_P2(2,2)) << "\t" 
+                    << sqrt(cov_Q2(0,0)) << "\t" << sqrt(cov_Q2(1,1)) << "\t" << sqrt(cov_Q2(2,2)) << "\t" 
+                    << sqrt(cov_AB2(0,0)) << "\t" << sqrt(cov_AB2(1,1)) << "\t" << sqrt(cov_AB2(2,2)) << "\t" 
+                    << sqrt(cov_GB2(0,0)) << "\t" << sqrt(cov_GB2(1,1)) << "\t" << sqrt(cov_GB2(2,2)) << std::endl;*/
+        #endif
+     }
+
+    #ifdef OUTPUT_DATA
+    debug_results.close();
+    #endif
+
+     //just print measurement covariances of IMU and odometry :
+    ConstraintBaseList ctr_list = origin_KF->getConstrainedByList();
+    for (auto ctr_it = ctr_list.begin(); ctr_it != ctr_list.end(); ctr_it++)
+    {
+        if ((*ctr_it)->getTypeId() == CTR_ODOM_3D) //change covariances in features to constraint only position
+            {
+                Eigen::MatrixXs meas_cov((*ctr_it)->getMeasurementCovariance());
+                std::cout << "\n Odom3D meas cov : " << meas_cov.diagonal().transpose() << std::endl;
+            }
+
+            else if ((*ctr_it)->getTypeId() == CTR_IMU)
+            {
+                Eigen::MatrixXs IMUmeas_cov((*ctr_it)->getMeasurementCovariance());
+                std::cout << "\n imu meas cov : " << IMUmeas_cov.diagonal().transpose() << std::endl;
+            }
+    }
+
+    //Assertions : estimations we expect in the ideal case
+    EXPECT_TRUE((last_KF->getPPtr()->getState() - expected_final_state.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) << "last_KF Pos : " << last_KF->getPPtr()->getState().transpose() <<
+    "\n expected Pos : " << expected_final_state.head(3).transpose() << std::endl;
+    EXPECT_TRUE((last_KF->getOPtr()->getState() - expected_final_state.segment(3,4)).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) << "last_KF Ori : " << last_KF->getOPtr()->getState().transpose() <<
+    "\n expected Ori : " << expected_final_state.segment(3,4).transpose() << std::endl;
+}
+
+int main(int argc, char **argv)
+{
+  ::testing::InitGoogleTest(&argc, argv);
+  ::testing::GTEST_FLAG(filter) = "ProcessorIMU_Real_CaptureFix_odom*";
+  //google::InitGoogleLogging(argv[0]);
+  return RUN_ALL_TESTS();
+}
diff --git a/src/test/gtest_imu_tools.cpp b/src/test/gtest_imu_tools.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b44ddfebb8052a49957c2130bc2b9a6beced5cf4
--- /dev/null
+++ b/src/test/gtest_imu_tools.cpp
@@ -0,0 +1,209 @@
+/*
+ * gtest_imu_tools.cpp
+ *
+ *  Created on: Jul 29, 2017
+ *      Author: jsola
+ */
+
+#include "imu_tools.h"
+
+#include "utils_gtest.h"
+
+
+using namespace Eigen;
+using namespace wolf;
+using namespace imu;
+
+TEST(IMU_tools, identity)
+{
+    VectorXs id_true;
+    id_true.setZero(10);
+    id_true(6) = 1.0;
+
+    VectorXs id = identity<Scalar>();
+    ASSERT_MATRIX_APPROX(id, id_true, 1e-10);
+}
+
+TEST(IMU_tools, identity_split)
+{
+    VectorXs p(3), qv(4), v(3);
+    Quaternions q;
+
+    identity(p,q,v);
+    ASSERT_MATRIX_APPROX(p, Vector3s::Zero(), 1e-10);
+    ASSERT_QUATERNION_APPROX(q, Quaternions::Identity(), 1e-10);
+    ASSERT_MATRIX_APPROX(v, Vector3s::Zero(), 1e-10);
+
+    identity(p,qv,v);
+    ASSERT_MATRIX_APPROX(p , Vector3s::Zero(), 1e-10);
+    ASSERT_MATRIX_APPROX(qv, (Vector4s()<<0,0,0,1).finished(), 1e-10);
+    ASSERT_MATRIX_APPROX(v , Vector3s::Zero(), 1e-10);
+}
+
+TEST(IMU_tools, inverse)
+{
+    VectorXs d(10), id(10), iid(10), iiid(10), I(10);
+    Vector4s qv;
+    Scalar dt = 0.1;
+
+    qv = (Vector4s() << 3, 4, 5, 6).finished().normalized();
+    d << 0, 1, 2, qv, 7, 8, 9;
+
+    id   = inverse(d, dt);
+
+    compose(id, d, dt, I);
+    ASSERT_MATRIX_APPROX(I, identity(), 1e-10);
+    compose(d, id, -dt, I); // Observe -dt is reversed !!
+    ASSERT_MATRIX_APPROX(I, identity(), 1e-10);
+
+    inverse(id, -dt, iid); // Observe -dt is reversed !!
+    ASSERT_MATRIX_APPROX( d,  iid, 1e-10);
+    iiid = inverse(iid, dt);
+    ASSERT_MATRIX_APPROX(id, iiid, 1e-10);
+}
+
+TEST(IMU_tools, compose_between)
+{
+    VectorXs dx1(10), dx2(10), dx3(10);
+    Matrix<Scalar, 10, 1> d1, d2, d3;
+    Vector4s qv;
+    Scalar dt = 0.1;
+
+    qv = (Vector4s() << 3, 4, 5, 6).finished().normalized();
+    dx1 << 0, 1, 2, qv, 7, 8, 9;
+    d1 = dx1;
+    qv = (Vector4s() << 6, 5, 4, 3).finished().normalized();
+    dx2 << 9, 8, 7, qv, 2, 1, 0;
+    d2 = dx2;
+
+    // combinations of templates for sum()
+    compose(dx1, dx2, dt, dx3);
+    compose(d1, d2, dt, d3);
+    ASSERT_MATRIX_APPROX(d3, dx3, 1e-10);
+
+    compose(d1, dx2, dt, dx3);
+    d3 = compose(dx1, d2, dt);
+    ASSERT_MATRIX_APPROX(d3, dx3, 1e-10);
+
+    // minus(d1, d3) should recover delta_2
+    VectorXs diffx(10);
+    Matrix<Scalar,10,1> diff;
+    between(d1, d3, dt, diff);
+    ASSERT_MATRIX_APPROX(diff, d2, 1e-10);
+
+    // minus(d3, d1, -dt) should recover inverse(d2, dt)
+    diff = between(d3, d1, -dt);
+    ASSERT_MATRIX_APPROX(diff, inverse(d2, dt), 1e-10);
+}
+
+TEST(IMU_tools, compose_between_with_state)
+{
+    VectorXs x(10), d(10), x2(10), x3(10), d2(10), d3(10);
+    Vector4s qv;
+    Scalar dt = 0.1;
+
+    qv = (Vector4s() << 3, 4, 5, 6).finished().normalized();
+    x << 0, 1, 2, qv, 7, 8, 9;
+    qv = (Vector4s() << 6, 5, 4, 3).finished().normalized();
+    d << 9, 8, 7, qv, 2, 1, 0;
+
+    composeOverState(x, d, dt, x2);
+    x3 = composeOverState(x, d, dt);
+    ASSERT_MATRIX_APPROX(x3, x2, 1e-10);
+
+    // betweenStates(x, x2) should recover d
+    betweenStates(x, x2, dt, d2);
+    d3 = betweenStates(x, x2, dt);
+    ASSERT_MATRIX_APPROX(d2, d, 1e-10);
+    ASSERT_MATRIX_APPROX(d3, d, 1e-10);
+    ASSERT_MATRIX_APPROX(betweenStates(x, x2, dt), d, 1e-10);
+
+    // x + (x2 - x) = x2
+    ASSERT_MATRIX_APPROX(composeOverState(x, betweenStates(x, x2, dt), dt), x2, 1e-10);
+
+    // (x + d) - x = d
+    ASSERT_MATRIX_APPROX(betweenStates(x, composeOverState(x, d, dt), dt), d, 1e-10);
+}
+
+TEST(IMU_tools, lift_retract)
+{
+    VectorXs d_min(9); d_min << 0, 1, 2, .3, .4, .5, 6, 7, 8; // use angles in the ball theta < pi
+
+    // transform to delta
+    VectorXs delta = retract(d_min);
+
+    // expected delta
+    Vector3s dp = d_min.head(3);
+    Quaternions dq = v2q(d_min.segment(3,3));
+    Vector3s dv = d_min.tail(3);
+    VectorXs delta_true(10); delta_true << dp, dq.coeffs(), dv;
+    ASSERT_MATRIX_APPROX(delta, delta_true, 1e-10);
+
+    // transform to a new tangent -- should be the original tangent
+    VectorXs d_from_delta = lift(delta);
+    ASSERT_MATRIX_APPROX(d_from_delta, d_min, 1e-10);
+
+    // transform to a new delta -- should be the previous delta
+    VectorXs delta_from_d = retract(d_from_delta);
+    ASSERT_MATRIX_APPROX(delta_from_d, delta, 1e-10);
+}
+
+TEST(IMU_tools, diff)
+{
+    VectorXs d1(10), d2(10);
+    Vector4s qv = (Vector4s() << 3, 4, 5, 6).finished().normalized();
+    d1 << 0, 1, 2, qv, 7, 8, 9;
+    d2 = d1;
+
+    VectorXs err(9);
+    diff(d1, d2, err);
+    ASSERT_MATRIX_APPROX(err, VectorXs::Zero(9), 1e-10);
+    ASSERT_MATRIX_APPROX(diff(d1, d2), VectorXs::Zero(9), 1e-10);
+}
+
+TEST(IMU_tools, compose_jacobians)
+{
+    VectorXs d1(10), d2(10), d3(10), d1_pert(10), d2_pert(10), d3_pert(10); // deltas
+    VectorXs t1(9), t2(9); // tangents
+    Matrix<Scalar, 9, 9> J1_a, J2_a, J1_n, J2_n;
+    Vector4s qv1, qv2;
+    Scalar dt = 0.1;
+    Scalar dx = 1e-6;
+    qv1 = (Vector4s() << 3, 4, 5, 6).finished().normalized();
+    d1 << 0, 1, 2, qv1, 7, 8, 9;
+    qv2 = (Vector4s() << 1, 2, 3, 4).finished().normalized();
+    d2 << 9, 8, 7, qv2, 2, 1, 0;
+
+    // analytical jacobians
+    compose(d1, d2, dt, d3, J1_a, J2_a);
+
+    // numerical jacobians
+    for (unsigned int i = 0; i<9; i++)
+    {
+        t1      . setZero();
+        t1(i)   = dx;
+
+        // Jac wrt first delta
+        d1_pert = plus(d1, t1);                 //     (d1 + t1)
+        d3_pert = compose(d1_pert, d2, dt);     //     (d1 + t1) + d2
+        t2      = diff(d3, d3_pert);            //   { (d2 + t1) + d2 } - { d1 + d2 }
+        J1_n.col(i) = t2/dx;                    // [ { (d2 + t1) + d2 } - { d1 + d2 } ] / dx
+
+        // Jac wrt second delta
+        d2_pert = plus(d2, t1);                 //          (d2 + t1)
+        d3_pert = compose(d1, d2_pert, dt);     //     d1 + (d2 + t1)
+        t2      = diff(d3, d3_pert);            //   { d1 + (d2 + t1) } - { d1 + d2 }
+        J2_n.col(i) = t2/dx;                    // [ { d1 + (d2 + t1) } - { d1 + d2 } ] / dx
+    }
+
+    // check that numerical and analytical match
+    ASSERT_MATRIX_APPROX(J1_a, J1_n, 1e-4);
+    ASSERT_MATRIX_APPROX(J2_a, J2_n, 1e-4);
+}
+
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  return RUN_ALL_TESTS();
+}
+
diff --git a/src/test/gtest_motion_buffer.cpp b/src/test/gtest_motion_buffer.cpp
index d6fa479efd37dd79c736ee44da7e9f068faa07ba..a0537489796786dcaaf9f935ad6a5665c1a286bc 100644
--- a/src/test/gtest_motion_buffer.cpp
+++ b/src/test/gtest_motion_buffer.cpp
@@ -21,7 +21,7 @@ using namespace wolf;
 
 Motion newMotion(TimeStamp t, Scalar d, Scalar D, Scalar C, Scalar J_d, Scalar J_D)
 {
-    Motion m(t, 1, 1);
+    Motion m(t, 1, 1, 1, 0);
     m.delta_(0) = d;
     m.delta_integr_(0) = D;
     m.delta_cov_(0) = C;
@@ -41,7 +41,7 @@ Motion m4 = newMotion(t4, 4, 10, 1, .1, 1);
 
 TEST(MotionBuffer, QueryTimeStamps)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     MB.get().push_back(m1);
@@ -65,7 +65,7 @@ TEST(MotionBuffer, QueryTimeStamps)
 
 TEST(MotionBuffer, getMotion)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     ASSERT_EQ(MB.getMotion(t0).delta_, m0.delta_);
@@ -79,7 +79,7 @@ TEST(MotionBuffer, getMotion)
 
 TEST(MotionBuffer, getDelta)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
 
@@ -93,7 +93,7 @@ TEST(MotionBuffer, getDelta)
 
 TEST(MotionBuffer, Split)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     MB.get().push_back(m1);
@@ -101,7 +101,7 @@ TEST(MotionBuffer, Split)
     MB.get().push_back(m3);
     MB.get().push_back(m4); // put 5 motions
 
-    MotionBuffer MB_old(1,1);
+    MotionBuffer MB_old(1,1,1,0);
 
     TimeStamp t = 1.5; // between m1 and m2
     MB.split(t, MB_old);
@@ -117,7 +117,7 @@ TEST(MotionBuffer, Split)
 
 TEST(MotionBuffer, integrateCovariance)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     MB.get().push_back(m1);
@@ -132,7 +132,7 @@ TEST(MotionBuffer, integrateCovariance)
 
 TEST(MotionBuffer, integrateCovariance_ts)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     MB.get().push_back(m1);
@@ -146,7 +146,7 @@ TEST(MotionBuffer, integrateCovariance_ts)
 
 TEST(MotionBuffer, integrateCovariance_ti_tf)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     MB.get().push_back(m1);
@@ -163,7 +163,7 @@ TEST(MotionBuffer, integrateCovariance_ti_tf)
 
 TEST(MotionBuffer, print)
 {
-    MotionBuffer MB(1,1);
+    MotionBuffer MB(1,1,1,0);
 
     MB.get().push_back(m0);
     MB.get().push_back(m1);
diff --git a/src/test/gtest_odom_2D.cpp b/src/test/gtest_odom_2D.cpp
index 19b0e1c8b96447e442b3f983e9d345da239c047f..eac322008965686b4b63458258de20a1c62af99e 100644
--- a/src/test/gtest_odom_2D.cpp
+++ b/src/test/gtest_odom_2D.cpp
@@ -135,7 +135,7 @@ TEST(Odom2D, ConstraintFix_and_ConstraintOdom2D)
     FrameBasePtr        F1 = Pr->emplaceFrame(KEY_FRAME, Vector3s::Zero(), t);
     CaptureBasePtr      C1 = F1->addCapture(std::make_shared<CaptureBase>("ODOM 2D", t));
     FeatureBasePtr      f1 = C1->addFeature(std::make_shared<FeatureBase>("ODOM 2D", delta, delta_cov));
-    ConstraintBasePtr   c1 = f1->addConstraint(std::make_shared<ConstraintOdom2D>(f1, F0));
+    ConstraintBasePtr   c1 = f1->addConstraint(std::make_shared<ConstraintOdom2D>(f1, F0, nullptr));
     F0->addConstrainedBy(c1);
 
     // KF2 and motion from KF1
@@ -144,7 +144,7 @@ TEST(Odom2D, ConstraintFix_and_ConstraintOdom2D)
     FrameBasePtr        F2 = Pr->emplaceFrame(KEY_FRAME, Vector3s::Zero(), t);
     CaptureBasePtr      C2 = F2->addCapture(std::make_shared<CaptureBase>("ODOM 2D", t));
     FeatureBasePtr      f2 = C2->addFeature(std::make_shared<FeatureBase>("ODOM 2D", delta, delta_cov));
-    ConstraintBasePtr   c2 = f2->addConstraint(std::make_shared<ConstraintOdom2D>(f2, F1));
+    ConstraintBasePtr   c2 = f2->addConstraint(std::make_shared<ConstraintOdom2D>(f2, F1, nullptr));
     F1->addConstrainedBy(c2);
 
     ASSERT_TRUE(Pr->check(0));
@@ -194,8 +194,11 @@ TEST(Odom2D, VoteForKfAndSolve)
     SensorBasePtr sensor_odom2d = problem->installSensor("ODOM 2D", "odom", Vector3s(0,0,0));
     ProcessorParamsOdom2DPtr params(std::make_shared<ProcessorParamsOdom2D>());
     params->dist_traveled_th_   = 100;
+    params->theta_traveled_th_  = 6.28;
     params->elapsed_time_th_    = 2.5*dt; // force KF at every third process()
     params->cov_det_th_         = 100;
+    params->unmeasured_perturbation_std_ = 0.001;
+    Matrix3s unmeasured_cov = params->unmeasured_perturbation_std_*params->unmeasured_perturbation_std_*Matrix3s::Identity();
     ProcessorBasePtr prc_base = problem->installProcessor("ODOM 2D", "odom", sensor_odom2d, params);
     ProcessorOdom2DPtr processor_odom2d = std::static_pointer_cast<ProcessorOdom2D>(prc_base);
 
@@ -229,7 +232,7 @@ TEST(Odom2D, VoteForKfAndSolve)
 
     t += dt;
     // Capture to use as container for all incoming data
-    CaptureMotionPtr capture = std::make_shared<CaptureMotion>(t, sensor_odom2d, data, data_cov, 7, 6, nullptr);
+    CaptureMotionPtr capture = std::make_shared<CaptureMotion>(t, sensor_odom2d, data, data_cov, 2, 3, 3, 0, nullptr);
 
     for (int n=1; n<=N; n++)
     {
@@ -240,7 +243,8 @@ TEST(Odom2D, VoteForKfAndSolve)
         // Processor
         sensor_odom2d->process(capture);
         ASSERT_TRUE(problem->check(0));
-        Matrix3s odom2d_delta_cov = processor_odom2d->integrateBufferCovariance(processor_odom2d->getBuffer());
+//        Matrix3s odom2d_delta_cov = processor_odom2d->integrateBufferCovariance(processor_odom2d->getBuffer());
+        Matrix3s odom2d_delta_cov = processor_odom2d->getMotion().delta_integr_cov_;
         //        std::cout << "State(" << (t - t0) << ") : " << processor_odom2d->getCurrentState().transpose() << std::endl;
         //        std::cout << "PRC  cov: \n" << odom2d_delta_cov << std::endl;
 
@@ -255,7 +259,7 @@ TEST(Odom2D, VoteForKfAndSolve)
             Ju = plus_jac_u(integrated_delta, data);
             Jx = plus_jac_x(integrated_delta, data);
             integrated_delta = plus(integrated_delta, data);
-            integrated_delta_cov = Jx * integrated_delta_cov * Jx.transpose() + Ju * data_cov * Ju.transpose();
+            integrated_delta_cov = Jx * integrated_delta_cov * Jx.transpose() + Ju * data_cov * Ju.transpose() + unmeasured_cov;
         }
 
         ASSERT_POSE2D_APPROX(processor_odom2d->getMotion().delta_integr_, integrated_delta, 1e-6);
@@ -265,7 +269,7 @@ TEST(Odom2D, VoteForKfAndSolve)
         Ju = plus_jac_u(integrated_pose, data);
         Jx = plus_jac_x(integrated_pose, data);
         integrated_pose = plus(integrated_pose, data);
-        integrated_cov = Jx * integrated_cov * Jx.transpose() + Ju * data_cov * Ju.transpose();
+        integrated_cov = Jx * integrated_cov * Jx.transpose() + Ju * data_cov * Ju.transpose() + unmeasured_cov;
 
         ASSERT_POSE2D_APPROX(processor_odom2d->getCurrentState(), integrated_pose, 1e-6);
 
@@ -311,9 +315,12 @@ TEST(Odom2D, KF_callback)
     ProblemPtr problem = Problem::create("PO 2D");
     SensorBasePtr sensor_odom2d = problem->installSensor("ODOM 2D", "odom", Vector3s(0,0,0));
     ProcessorParamsOdom2DPtr params(std::make_shared<ProcessorParamsOdom2D>());
-    params->dist_traveled_th_   = 100; // don't make keyframes
+    params->dist_traveled_th_   = 100;
+    params->theta_traveled_th_  = 6.28;
     params->elapsed_time_th_    = 100;
     params->cov_det_th_         = 100;
+    params->unmeasured_perturbation_std_ = 0.001;
+    Matrix3s unmeasured_cov = params->unmeasured_perturbation_std_*params->unmeasured_perturbation_std_*Matrix3s::Identity();
     ProcessorBasePtr prc_base = problem->installProcessor("ODOM 2D", "odom", sensor_odom2d, params);
     ProcessorOdom2DPtr processor_odom2d = std::static_pointer_cast<ProcessorOdom2D>(prc_base);
 
@@ -340,7 +347,7 @@ TEST(Odom2D, KF_callback)
 //    std::cout << "\nIntegrating data..." << std::endl;
 
     // Capture to use as container for all incoming data
-    CaptureMotionPtr capture = std::make_shared<CaptureMotion>(t, sensor_odom2d, data, data_cov, 7, 6, nullptr);
+    CaptureMotionPtr capture = std::make_shared<CaptureMotion>(t, sensor_odom2d, data, data_cov, 2, 3, 3, 0, nullptr);
 
     for (int n=1; n<=N; n++)
     {
@@ -357,13 +364,13 @@ TEST(Odom2D, KF_callback)
         Ju = plus_jac_u(integrated_delta, data);
         Jx = plus_jac_x(integrated_delta, data);
         integrated_delta = plus(integrated_delta, data);
-        integrated_delta_cov = Jx * integrated_delta_cov * Jx.transpose() + Ju * data_cov * Ju.transpose();
+        integrated_delta_cov = Jx * integrated_delta_cov * Jx.transpose() + Ju * data_cov * Ju.transpose() + unmeasured_cov;
 
         // Integrate pose
         Ju = plus_jac_u(integrated_pose, data);
         Jx = plus_jac_x(integrated_pose, data);
         integrated_pose = plus(integrated_pose, data);
-        integrated_cov = Jx * integrated_cov * Jx.transpose() + Ju * data_cov * Ju.transpose();
+        integrated_cov = Jx * integrated_cov * Jx.transpose() + Ju * data_cov * Ju.transpose() + unmeasured_cov;
 
         // Store integrals
         integrated_pose_vector.push_back(integrated_pose);
@@ -404,6 +411,7 @@ TEST(Odom2D, KF_callback)
     t_split = t0 + m_split*dt;
 //    std::cout << "-----------------------------\nSplit between KFs; time: " << t_split - t0 << std::endl;
 
+//    problem->print(4,1,1,0);
 
     x_split = processor_odom2d->getState(t_split);
     FrameBasePtr keyframe_1 = problem->emplaceFrame(KEY_FRAME, x_split, t_split);
@@ -427,12 +435,22 @@ TEST(Odom2D, KF_callback)
 //    show(problem);
 
     // check the split KF
-    ASSERT_POSE2D_APPROX(keyframe_1->getState()                 , integrated_pose_vector[m_split], 1e-6);
-    ASSERT_MATRIX_APPROX(problem->getFrameCovariance(keyframe_1) , integrated_cov_vector [m_split], 1e-6);
+    ASSERT_POSE2D_APPROX(keyframe_1->getState()                  , integrated_pose_vector[m_split], 1e-6);
+    ASSERT_MATRIX_APPROX(problem->getFrameCovariance(keyframe_1) , integrated_cov_vector [m_split], 1e-6); // FIXME test does not pass
 
     // check other KF in the future of the split KF
     ASSERT_POSE2D_APPROX(problem->getLastKeyFramePtr()->getState() , integrated_pose_vector[n_split], 1e-6);
-    ASSERT_MATRIX_APPROX(problem->getFrameCovariance(keyframe_2)    , integrated_cov_vector [n_split], 1e-6);
+    ASSERT_MATRIX_APPROX(problem->getFrameCovariance(keyframe_2)   , integrated_cov_vector [n_split], 1e-6);
+
+    // Check full trajectory
+    t = t0;
+    for (int n=1; n<=N; n++)
+    {
+        t += dt;
+        //        WOLF_DEBUG("   estimated(", t, ") = ", problem->getState(t).transpose());
+        //        WOLF_DEBUG("ground truth(", t, ") = ", integrated_pose_vector[n].transpose());
+        ASSERT_MATRIX_APPROX(problem->getState(t), integrated_pose_vector[n], 1e-6);
+    }
 }
 
 
diff --git a/src/test/gtest_odom_3D.cpp b/src/test/gtest_odom_3D.cpp
index 0632acd149f425954c39cbd98e965e045d38bf77..544c4b47ad80af6e25c32b4f3e963b0562444f17 100644
--- a/src/test/gtest_odom_3D.cpp
+++ b/src/test/gtest_odom_3D.cpp
@@ -93,11 +93,16 @@ TEST(ProcessorOdom3D, data2delta)
     Matrix6s data_cov = diag.asDiagonal();
     Matrix6s delta_cov = data_cov;
 
+    // return values for data2delta()
+    VectorXs delta_ret(7);
+    MatrixXs delta_cov_ret(6,6);
+    MatrixXs jac_delta_calib(6,0);
+
     // call the function under test
-    prc.data2delta(data, data_cov, dt);
+    prc.data2delta(data, data_cov, dt, delta_ret, delta_cov_ret, VectorXs::Zero(0), jac_delta_calib);
 
-    ASSERT_TRUE((prc.delta() - delta).isMuchSmallerThan(1, Constants::EPS_SMALL));
-    ASSERT_TRUE((prc.deltaCov() - delta_cov).isMuchSmallerThan(1, Constants::EPS_SMALL));
+    ASSERT_MATRIX_APPROX(delta_ret , delta, Constants::EPS_SMALL);
+    ASSERT_MATRIX_APPROX(delta_cov_ret , delta_cov, Constants::EPS_SMALL);
 
 }
 
@@ -121,9 +126,9 @@ TEST(ProcessorOdom3D, deltaPlusDelta)
 
     prc.deltaPlusDelta(D, d, dt, D_int);
 
-    ASSERT_TRUE((D_int - D_int_check).isMuchSmallerThan(1, 1e-10))
-        << "\nDpd  : " << D_int.transpose()
-        << "\ncheck: " << D_int_check.transpose();
+    ASSERT_MATRIX_APPROX(D_int , D_int_check, 1e-10);
+//        << "\nDpd  : " << D_int.transpose()
+//        << "\ncheck: " << D_int_check.transpose();
 }
 
 TEST(ProcessorOdom3D, deltaPlusDelta_Jac)
@@ -162,7 +167,7 @@ TEST(ProcessorOdom3D, Interpolate0) // basic test
 
     ProcessorOdom3D prc;
 
-    Motion ref(0,7,6), final(0,7,6), interpolated(0,7,6);
+    Motion ref(0.0,6,7,6,0), final(0.0,6,7,6,0), interpolated(0.0,6,7,6,0);
 
     // set ref
     ref.ts_ = 1;
@@ -193,8 +198,8 @@ TEST(ProcessorOdom3D, Interpolate0) // basic test
     WOLF_DEBUG("interpolated Delta= ", interpolated.delta_integr_.transpose());
 
     // delta
-    ASSERT_TRUE((interpolated.delta_.head<3>() - 0.25 * final.delta_.head<3>()).isMuchSmallerThan(1.0, Constants::EPS));
-    ASSERT_TRUE((second.delta_.head<3>()       - 0.75 * final.delta_.head<3>()).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(interpolated.delta_.head<3>() , 0.25 * final.delta_.head<3>(), Constants::EPS);
+    ASSERT_MATRIX_APPROX(second.delta_.head<3>()       , 0.75 * final.delta_.head<3>(), Constants::EPS);
 
 }
 
@@ -216,15 +221,15 @@ TEST(ProcessorOdom3D, Interpolate1) // delta algebra test
     // absolute poses: origin, ref, interp, second=final
     Vector7s    x_o, x_r, x_i, x_s, x_f;
     Map<Vector3s>       p_o(x_o.data(), 3);
-    Map<Quaternions>    q_o(x_o.data()+3);
+    Map<Quaternions>    q_o(x_o.data() +3);
     Map<Vector3s>       p_r(x_r.data(), 3);
-    Map<Quaternions>    q_r(x_r.data()+3);
+    Map<Quaternions>    q_r(x_r.data() +3);
     Map<Vector3s>       p_i(x_i.data(), 3);
-    Map<Quaternions>    q_i(x_i.data()+3);
+    Map<Quaternions>    q_i(x_i.data() +3);
     Map<Vector3s>       p_s(x_s.data(), 3);
-    Map<Quaternions>    q_s(x_s.data()+3);
+    Map<Quaternions>    q_s(x_s.data() +3);
     Map<Vector3s>       p_f(x_f.data(), 3);
-    Map<Quaternions>    q_f(x_f.data()+3);
+    Map<Quaternions>    q_f(x_f.data() +3);
 
     // deltas -- referred to previous delta
     //         o-r    r-i    i-s    s-f
@@ -264,7 +269,7 @@ TEST(ProcessorOdom3D, Interpolate1) // delta algebra test
     Vector3s w;
 
     // Motion structures
-    Motion R(0,7,6), I(0,7,6), S(0,7,6), F(0,7,6);
+    Motion R(0.0,6,7,6,0), I(0.0,6,7,6,0), S(0.0,6,7,6,0), F(0.0,6,7,6,0);
 
 
     /////////// start experiment ///////////////
@@ -311,9 +316,9 @@ TEST(ProcessorOdom3D, Interpolate1) // delta algebra test
     Dq_of = q_o.conjugate() *  q_f;
 
 
-    R.resize(7,6);
-    F.resize(7,6);
-    I.resize(7,6);
+    R.resize(6,7,6,0);
+    F.resize(6,7,6,0);
+    I.resize(6,7,6,0);
 
     // set ref
     R.ts_           = t_r;
@@ -322,11 +327,11 @@ TEST(ProcessorOdom3D, Interpolate1) // delta algebra test
 
     WOLF_DEBUG("* R.d = ", R.delta_.transpose());
     WOLF_DEBUG("  or  = ", dx_or.transpose());
-    ASSERT_TRUE((R.delta_        - dx_or).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(R.delta_        , dx_or, Constants::EPS);
 
     WOLF_DEBUG("  R.D = ", R.delta_integr_.transpose());
     WOLF_DEBUG("  or  = ", Dx_or.transpose());
-    ASSERT_TRUE((R.delta_integr_ - Dx_or).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(R.delta_integr_ , Dx_or, Constants::EPS);
 
     // set final
     F.ts_           = t_f;
@@ -335,20 +340,20 @@ TEST(ProcessorOdom3D, Interpolate1) // delta algebra test
 
     WOLF_DEBUG("* F.d = ", F.delta_.transpose());
     WOLF_DEBUG("  rf  = ", dx_rf.transpose());
-    ASSERT_TRUE((F.delta_        - dx_rf).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(F.delta_        , dx_rf, Constants::EPS);
 
     WOLF_DEBUG("  F.D = ", F.delta_integr_.transpose());
     WOLF_DEBUG("  of  = ", Dx_of.transpose());
-    ASSERT_TRUE((F.delta_integr_ - Dx_of).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(F.delta_integr_ , Dx_of, Constants::EPS);
 
     S = F; // avoid overwriting final
     WOLF_DEBUG("* S.d = ", S.delta_.transpose());
     WOLF_DEBUG("  rs  = ", dx_rs.transpose());
-    ASSERT_TRUE((S.delta_        - dx_rs).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_        , dx_rs, Constants::EPS);
 
     WOLF_DEBUG("  S.D = ", S.delta_integr_.transpose());
     WOLF_DEBUG("  os  = ", Dx_os.transpose());
-    ASSERT_TRUE((S.delta_integr_ - Dx_os).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_integr_ , Dx_os, Constants::EPS);
 
     // interpolate!
     WOLF_DEBUG("*** INTERPOLATE *** I has been computed; S has changed.");
@@ -356,19 +361,19 @@ TEST(ProcessorOdom3D, Interpolate1) // delta algebra test
 
     WOLF_DEBUG("* I.d = ", I.delta_.transpose());
     WOLF_DEBUG("  ri  = ", dx_ri.transpose());
-    ASSERT_TRUE((I.delta_        - dx_ri).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(I.delta_        , dx_ri, Constants::EPS);
 
     WOLF_DEBUG("  I.D = ", I.delta_integr_.transpose());
     WOLF_DEBUG("  oi  = ", Dx_oi.transpose());
-    ASSERT_TRUE((I.delta_integr_ - Dx_oi).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(I.delta_integr_ , Dx_oi, Constants::EPS);
 
     WOLF_DEBUG("* S.d = ", S.delta_.transpose());
     WOLF_DEBUG("  is  = ", dx_is.transpose());
-    ASSERT_TRUE((S.delta_        - dx_is).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_        , dx_is, Constants::EPS);
 
     WOLF_DEBUG("  S.D = ", S.delta_integr_.transpose());
     WOLF_DEBUG("  os  = ", Dx_os.transpose());
-    ASSERT_TRUE((S.delta_integr_ - Dx_os).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_integr_ , Dx_os, Constants::EPS);
 
 }
 
@@ -402,7 +407,7 @@ TEST(ProcessorOdom3D, Interpolate2) // timestamp out of bounds test
     WOLF_DEBUG("t_o: ", t_o.get(), "; t_r: ", t_r.get(), "; t_f: ", t_f.get());
 
     // Motion structures
-    Motion R(0,7,6), I(0,7,6), S(0,7,6), F(0,7,6);
+    Motion R(0.0,6,7,6,0), I(0.0,6,7,6,0), S(0.0,6,7,6,0), F(0.0,6,7,6,0);
 
 
     /////////// start experiment ///////////////
@@ -414,10 +419,10 @@ TEST(ProcessorOdom3D, Interpolate2) // timestamp out of bounds test
     prc.deltaPlusDelta(Dx_or, dx_rf, t_f - t_r, Dx_of);
     Dx_os = Dx_of;
 
-    R.resize(7,6);
-    I.resize(7,6);
-    S.resize(7,6);
-    F.resize(7,6);
+    R.resize(6,7,6,0);
+    I.resize(6,7,6,0);
+    S.resize(6,7,6,0);
+    F.resize(6,7,6,0);
 
     // set ref
     R.ts_           = t_r;
@@ -426,11 +431,11 @@ TEST(ProcessorOdom3D, Interpolate2) // timestamp out of bounds test
 
     WOLF_DEBUG("* R.d = ", R.delta_.transpose());
     WOLF_DEBUG("  or  = ", dx_or.transpose());
-    ASSERT_TRUE((R.delta_        - dx_or).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(R.delta_        , dx_or, Constants::EPS);
 
     WOLF_DEBUG("  R.D = ", R.delta_integr_.transpose());
     WOLF_DEBUG("  or  = ", Dx_or.transpose());
-    ASSERT_TRUE((R.delta_integr_ - Dx_or).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(R.delta_integr_ , Dx_or, Constants::EPS);
 
     // set final
     F.ts_           = t_f;
@@ -439,20 +444,20 @@ TEST(ProcessorOdom3D, Interpolate2) // timestamp out of bounds test
 
     WOLF_DEBUG("* F.d = ", F.delta_.transpose());
     WOLF_DEBUG("  rf  = ", dx_rf.transpose());
-    ASSERT_TRUE((F.delta_        - dx_rf).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(F.delta_        , dx_rf, Constants::EPS);
 
     WOLF_DEBUG("  F.D = ", F.delta_integr_.transpose());
     WOLF_DEBUG("  of  = ", Dx_of.transpose());
-    ASSERT_TRUE((F.delta_integr_ - Dx_of).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(F.delta_integr_ , Dx_of, Constants::EPS);
 
     S = F; // avoid overwriting final
     WOLF_DEBUG("* S.d = ", S.delta_.transpose());
     WOLF_DEBUG("  rs  = ", dx_rs.transpose());
-    ASSERT_TRUE((S.delta_        - dx_rs).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_        , dx_rs, Constants::EPS);
 
     WOLF_DEBUG("  S.D = ", S.delta_integr_.transpose());
     WOLF_DEBUG("  os  = ", Dx_os.transpose());
-    ASSERT_TRUE((S.delta_integr_ - Dx_os).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_integr_ , Dx_os, Constants::EPS);
 
     // interpolate!
     t_i = 0.5; /// before ref!
@@ -461,19 +466,19 @@ TEST(ProcessorOdom3D, Interpolate2) // timestamp out of bounds test
 
     WOLF_DEBUG("* I.d = ", I.delta_.transpose());
     WOLF_DEBUG("  ri  = ", prc.deltaZero().transpose());
-    ASSERT_TRUE((I.delta_  - prc.deltaZero()).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(I.delta_  , prc.deltaZero(), Constants::EPS);
 
     WOLF_DEBUG("  I.D = ", I.delta_integr_.transpose());
     WOLF_DEBUG("  oi  = ", Dx_or.transpose());
-    ASSERT_TRUE((I.delta_integr_ - Dx_or).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(I.delta_integr_ , Dx_or, Constants::EPS);
 
     WOLF_DEBUG("* S.d = ", S.delta_.transpose());
     WOLF_DEBUG("  is  = ", dx_rf.transpose());
-    ASSERT_TRUE((S.delta_        - dx_rf).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_        , dx_rf, Constants::EPS);
 
     WOLF_DEBUG("  S.D = ", S.delta_integr_.transpose());
     WOLF_DEBUG("  os  = ", Dx_of.transpose());
-    ASSERT_TRUE((S.delta_integr_ - Dx_of).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_integr_ , Dx_of, Constants::EPS);
 
     // interpolate!
     t_i = 5.5; /// after ref!
@@ -483,19 +488,19 @@ TEST(ProcessorOdom3D, Interpolate2) // timestamp out of bounds test
 
     WOLF_DEBUG("* I.d = ", I.delta_.transpose());
     WOLF_DEBUG("  ri  = ", dx_rf.transpose());
-    ASSERT_TRUE((I.delta_  - dx_rf).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(I.delta_  , dx_rf, Constants::EPS);
 
     WOLF_DEBUG("  I.D = ", I.delta_integr_.transpose());
     WOLF_DEBUG("  oi  = ", Dx_of.transpose());
-    ASSERT_TRUE((I.delta_integr_ - Dx_of).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(I.delta_integr_ , Dx_of, Constants::EPS);
 
     WOLF_DEBUG("* S.d = ", S.delta_.transpose());
     WOLF_DEBUG("  is  = ", prc.deltaZero().transpose());
-    ASSERT_TRUE((S.delta_ - prc.deltaZero()).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_ , prc.deltaZero(), Constants::EPS);
 
     WOLF_DEBUG("  S.D = ", S.delta_integr_.transpose());
     WOLF_DEBUG("  os  = ", Dx_of.transpose());
-    ASSERT_TRUE((S.delta_integr_ - Dx_of).isMuchSmallerThan(1.0, Constants::EPS));
+    ASSERT_MATRIX_APPROX(S.delta_integr_ , Dx_of, Constants::EPS);
 
 }
 
diff --git a/src/test/gtest_processorIMU_jacobians.cpp b/src/test/gtest_processorIMU_jacobians.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..2b602015b46afa27361a906d4166ebb57004ab06
--- /dev/null
+++ b/src/test/gtest_processorIMU_jacobians.cpp
@@ -0,0 +1,550 @@
+/**
+ * \file gtest_imu_preintegration_jacobians.cpp
+ *
+ *  Created on: Nov 29, 2016
+ *      \author: AtDinesh
+ */
+
+ //Wolf
+#include "wolf.h"
+#include "problem.h"
+#include "sensor_imu.h"
+#include "capture_imu.h"
+#include "state_block.h"
+#include "state_quaternion.h"
+#include "processor_imu_UnitTester.h"
+
+//std
+#include <iostream>
+#include <fstream>
+#include <iomanip>
+#include <ctime>
+#include <cmath>
+
+//google test
+#include "utils_gtest.h"
+
+//#define DEBUG_RESULTS
+//#define WRITE_RESULTS
+
+using namespace wolf;
+
+// A new one of these is created for each test
+class ProcessorIMU_jacobians : public testing::Test
+{
+    public:
+        TimeStamp t;
+        Eigen::Vector6s data_;
+        Eigen::Matrix<wolf::Scalar,10,1> Delta0;
+        wolf::Scalar ddelta_bias;
+        wolf::Scalar dt;
+        Eigen::Matrix<wolf::Scalar,9,1> Delta_noise;
+        Eigen::Matrix<wolf::Scalar,9,1> delta_noise;
+        struct IMU_jac_bias bias_jac;
+        struct IMU_jac_deltas deltas_jac;
+
+        void remapJacDeltas_quat0(IMU_jac_deltas& _jac_delta, Eigen::Map<Eigen::Quaternions>& _Dq0, Eigen::Map<Eigen::Quaternions>& _dq0){
+
+            new (&_Dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta0_.data() + 3);
+            new (&_dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta0_.data() + 3);
+        }
+
+        void remapJacDeltas_quat(IMU_jac_deltas& _jac_delta, Eigen::Map<Eigen::Quaternions>& _Dq, Eigen::Map<Eigen::Quaternions>& _dq, const int& place ){
+    
+            assert(place < _jac_delta.Delta_noisy_vect_.size());
+            new (&_Dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta_noisy_vect_(place).data() + 3);
+            new (&_dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta_noisy_vect_(place).data() + 3);
+        }
+
+    virtual void SetUp()
+    {
+        //SetUp for jacobians 
+        wolf::Scalar deg_to_rad = M_PI/180.0;
+        data_ << 10,0.5,3, 100*deg_to_rad,110*deg_to_rad,30*deg_to_rad;
+
+        // Wolf problem
+        ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs IMU_extrinsics(7);
+        IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot
+
+        ProcessorIMU_UnitTester processor_imu;
+        ddelta_bias = 0.00000001;
+        dt = 0.001;
+
+        //defining a random Delta to begin with (not to use Origin point)
+        Eigen::Matrix<wolf::Scalar,10,1> Delta0;
+        Delta0 = Eigen::Matrix<wolf::Scalar,10,1>::Random();
+        Delta0.head<3>() = Delta0.head<3>()*100;
+        Delta0.tail<3>() = Delta0.tail<3>()*10;
+        Eigen::Vector3s ang0, ang;
+        ang0 << 120.08*deg_to_rad, 12.36*deg_to_rad, 54.32*deg_to_rad; 
+
+        Eigen::Map<Eigen::Quaternions> Delta0_quat(Delta0.data()+3);
+        Delta0_quat = v2q(ang0);
+        Delta0_quat.normalize();
+        ang = q2v(Delta0_quat);
+
+        //std::cout << "\ninput Delta0 : " << Delta0 << std::endl;
+        //std::cout << "\n rotation vector we start with :\n" << ang << std::endl;
+
+        //get data to compute jacobians
+        struct IMU_jac_bias bias_jac_c = processor_imu.finite_diff_ab(dt, data_, ddelta_bias, Delta0);
+        bias_jac.copyfrom(bias_jac_c);
+
+        Delta_noise << 0.00000001, 0.00000001, 0.00000001,  0.0001, 0.0001, 0.0001,  0.00000001, 0.00000001, 0.00000001;
+        delta_noise << 0.00000001, 0.00000001, 0.00000001,  0.0001, 0.0001, 0.0001,  0.00000001, 0.00000001, 0.00000001;
+
+        struct IMU_jac_deltas deltas_jac_c = processor_imu.finite_diff_noise(dt, data_, Delta_noise, delta_noise, Delta0);
+        deltas_jac = deltas_jac_c;
+    }
+
+    virtual void TearDown()
+    {
+        // code here will be called just after the test completes
+        // ok to through exceptions from here if need be
+        /*
+            You can do deallocation of resources in TearDown or the destructor routine. 
+                However, if you want exception handling you must do it only in the TearDown code because throwing an exception 
+                from the destructor results in undefined behavior.
+            The Google assertion macros may throw exceptions in platforms where they are enabled in future releases. 
+                Therefore, it's a good idea to use assertion macros in the TearDown code for better maintenance.
+        */
+    }
+};
+
+
+class ProcessorIMU_jacobians_Dq : public testing::Test
+{
+    public:
+        TimeStamp t;
+        Eigen::Vector6s data_;
+        Eigen::Matrix<wolf::Scalar,10,1> Delta0;
+        wolf::Scalar ddelta_bias2;
+        wolf::Scalar dt;
+        struct IMU_jac_bias bias_jac2;
+
+        void remapJacDeltas_quat0(IMU_jac_deltas& _jac_delta, Eigen::Map<Eigen::Quaternions>& _Dq0, Eigen::Map<Eigen::Quaternions>& _dq0){
+
+            new (&_Dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta0_.data() + 3);
+            new (&_dq0) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta0_.data() + 3);
+        }
+
+        void remapJacDeltas_quat(IMU_jac_deltas& _jac_delta, Eigen::Map<Eigen::Quaternions>& _Dq, Eigen::Map<Eigen::Quaternions>& _dq, const int& place ){
+    
+            assert(place < _jac_delta.Delta_noisy_vect_.size());
+            new (&_Dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.Delta_noisy_vect_(place).data() + 3);
+            new (&_dq) Eigen::Map<const Eigen::Quaternions>(_jac_delta.delta_noisy_vect_(place).data() + 3);
+        }
+
+    virtual void SetUp()
+    {
+        //SetUp for jacobians 
+        wolf::Scalar deg_to_rad = M_PI/180.0;
+        data_ << 10,0.5,3, 100*deg_to_rad,110*deg_to_rad,30*deg_to_rad;
+
+        // Wolf problem
+        ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs IMU_extrinsics(7);
+        IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot
+
+        ProcessorIMU_UnitTester processor_imu;
+        ddelta_bias2 = 0.0001;
+        dt = 0.001;
+
+        //defining a random Delta to begin with (not to use Origin point)
+        Eigen::Matrix<wolf::Scalar,10,1> Delta0;
+        Delta0 = Eigen::Matrix<wolf::Scalar,10,1>::Random();
+        Delta0.head<3>() = Delta0.head<3>()*100;
+        Delta0.tail<3>() = Delta0.tail<3>()*10;
+        Eigen::Vector3s ang0, ang;
+        ang0 << 120.08*deg_to_rad, 12.36*deg_to_rad, 54.32*deg_to_rad; 
+
+        Eigen::Map<Eigen::Quaternions> Delta0_quat(Delta0.data()+3);
+        Delta0_quat = v2q(ang0);
+        Delta0_quat.normalize();
+        ang = q2v(Delta0_quat);
+
+        //std::cout << "\ninput Delta0 : " << Delta0 << std::endl;
+        //std::cout << "\n rotation vector we start with :\n" << ang << std::endl;
+
+        //get data to compute jacobians
+        struct IMU_jac_bias bias_jac_c = processor_imu.finite_diff_ab(dt, data_, ddelta_bias2, Delta0);
+        bias_jac2.copyfrom(bias_jac_c);
+    }
+
+    virtual void TearDown()
+    {
+        // code here will be called just after the test completes
+        // ok to through exceptions from here if need be
+        /*
+            You can do deallocation of resources in TearDown or the destructor routine. 
+                However, if you want exception handling you must do it only in the TearDown code because throwing an exception 
+                from the destructor results in undefined behavior.
+            The Google assertion macros may throw exceptions in platforms where they are enabled in future releases. 
+                Therefore, it's a good idea to use assertion macros in the TearDown code for better maintenance.
+        */
+    }
+};
+
+                            ///BIAS TESTS
+
+/*                              IMU_jac_deltas struct form :
+    contains vectors of size 7 :
+    Elements at place 0 are those not affected by the bias noise that we add (da_bx,..., dw_bx,... ).
+                place 1 : added da_bx in data         place 2 : added da_by in data       place 3 : added da_bz in data
+                place 4 : added dw_bx in data         place 5 : added dw_by in data       place 6 : added dw_bz in data
+*/
+
+/*                                  Mathematics
+
+        dDp_dab = [dDp_dab_x, dDp_dab_y, dDp_dab_z]
+        dDp_dab_x = (dDp(ab_x + dab_x, ab_y, ab_z) - dDp(ab_x,ab_y,ab_z)) / dab_x
+        dDp_dab_x = (dDp(ab_x, ab_y + dab_y, ab_z) - dDp(ab_x,ab_y,ab_z)) / dab_y
+        dDp_dab_x = (dDp(ab_x, ab_y, ab_z + dab_z) - dDp(ab_x,ab_y,ab_z)) / dab_z
+
+        similar for dDv_dab
+        note dDp_dab_x, dDp_dab_y, dDp_dab_z, dDv_dab_x, dDv_dab_y, dDv_dab_z are 3x1 vectors !
+
+        dDq_dab = 0_{3x3}
+        dDq_dwb = [dDq_dwb_x, dDq_dwb_y, dDq_dwb_z]
+        dDq_dwb_x = log( dR(wb).transpose() * dR(wb - dwb_x))/dwb_x
+                  = log( dR(wb).transpose() * exp((wx - wbx - dwb_x)dt, (wy - wby)dt, (wy - wby)dt))/dwb_x
+        dDq_dwb_y = log( dR(wb).transpose() * dR(wb - dwb_y))/dwb_y
+        dDq_dwb_z = log( dR(wb).transpose() * dR(wb + dwb_z))/dwb_z
+
+        Note : dDq_dwb must be computed recursively ! So comparing the one returned by processor_imu and the numerical 
+        one will have no sense if we aredoing this from a random Delta. The Delta here should be the origin.
+        dDq_dwb_ = dR.tr()*dDq_dwb - Jr(wdt)*dt
+        Then at first step, dR.tr() = Id, dDq_dwb = 0_{3x3}, which boils down to dDq_dwb_ = Jr(wdt)*dt 
+*/
+
+TEST_F(ProcessorIMU_jacobians, dDp_dab)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDp_dab;
+
+    for(int i=0;i<3;i++)
+         dDp_dab.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i).head(3) - bias_jac.Delta0_.head(3))/ddelta_bias;
+
+    ASSERT_TRUE((dDp_dab - bias_jac.dDp_dab_).isMuchSmallerThan(1,0.000001)) << "dDp_dab : \n" << dDp_dab << "\n bias_jac.dDp_dab_ :\n" << bias_jac.dDp_dab_ <<
+     "\ndDp_dab_a - dDp_dab_ : \n" << bias_jac.dDp_dab_ - dDp_dab << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDv_dab)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDv_dab;
+
+    for(int i=0;i<3;i++)
+         dDv_dab.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i).tail(3) - bias_jac.Delta0_.tail(3))/ddelta_bias;
+
+    ASSERT_TRUE((dDv_dab - bias_jac.dDv_dab_).isMuchSmallerThan(1,0.000001)) << "dDv_dab : \n" << dDv_dab << "\n bias_jac.dDv_dab_ :\n" << bias_jac.dDv_dab_ <<
+     "\ndDv_dab_a - dDv_dab_ : \n" << bias_jac.dDv_dab_ - dDv_dab << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDp_dwb)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDp_dwb;
+
+    for(int i=0;i<3;i++)
+         dDp_dwb.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i+3).head(3) - bias_jac.Delta0_.head(3))/ddelta_bias;
+
+    ASSERT_TRUE((dDp_dwb - bias_jac.dDp_dwb_).isMuchSmallerThan(1,0.000001)) << "dDp_dwb : \n" << dDp_dwb << "\n bias_jac.dDp_dwb_ :\n" << bias_jac.dDp_dwb_ <<
+     "\ndDp_dwb_a - dDv_dab_ : \n" << bias_jac.dDp_dwb_ - dDp_dwb << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDv_dwb_)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDv_dwb;
+
+    for(int i=0;i<3;i++)
+         dDv_dwb.block<3,1>(0,i) = (bias_jac.Deltas_noisy_vect_(i+3).tail(3) - bias_jac.Delta0_.tail(3))/ddelta_bias;
+
+    ASSERT_TRUE((dDv_dwb - bias_jac.dDv_dwb_).isMuchSmallerThan(1,0.000001)) << "dDv_dwb : \n" << dDv_dwb << "\n bias_jac.dDv_dwb_ :\n" << bias_jac.dDv_dwb_ <<
+     "\ndDv_dwb_a - dDv_dwb_ : \n" << bias_jac.dDv_dwb_ - dDv_dwb << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDq_dab)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> q_in_1(NULL), q_in_2(NULL);
+    Eigen::Matrix3s dDq_dab;
+
+    new (&q_in_1) Eigen::Map<Eigen::Quaternions>(bias_jac.Delta0_.data() + 3);
+    for(int i=0;i<3;i++){
+        new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac.Deltas_noisy_vect_(i).data() + 3);
+        dDq_dab.block<3,1>(0,i) = R2v( q_in_1.matrix().transpose() * q_in_2.matrix())/ddelta_bias;
+    }
+
+    ASSERT_TRUE(dDq_dab.isZero(wolf::Constants::EPS)) << "\t\tdDq_dab_ jacobian is not Zero :" << dDq_dab << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDq_dwb_noise_1Em8_)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> q_in_1(NULL), q_in_2(NULL);
+    Eigen::Matrix3s dDq_dwb;
+
+    new (&q_in_1) Eigen::Map<Eigen::Quaternions>(bias_jac.Delta0_.data() + 3);
+    for(int i=0;i<3;i++){
+        new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac.Deltas_noisy_vect_(i+3).data() + 3);
+        dDq_dwb.block<3,1>(0,i) = R2v( q_in_1.matrix().transpose() * q_in_2.matrix())/ddelta_bias;
+    }
+
+    ASSERT_FALSE((dDq_dwb - bias_jac.dDq_dwb_).isMuchSmallerThan(1,0.000001)) << "dDq_dwb : \n" << dDq_dwb << "\n bias_jac.dDq_dwb_ :\n" << bias_jac.dDq_dwb_ <<
+     "\ndDq_dwb_a - dDq_dwb_ : \n" << bias_jac.dDq_dwb_ - dDq_dwb << "\n R1^T * R2 : \n"  << q_in_1.matrix().transpose() * q_in_2.matrix() << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians_Dq, dDq_dwb_noise_1Em4_precision_1Em3_)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> q_in_1(NULL), q_in_2(NULL);
+    Eigen::Matrix3s dDq_dwb;
+
+    new (&q_in_1) Eigen::Map<Eigen::Quaternions>(bias_jac2.Delta0_.data() + 3);
+    for(int i=0;i<3;i++){
+        new (&q_in_2) Eigen::Map<Eigen::Quaternions>(bias_jac2.Deltas_noisy_vect_(i+3).data() + 3);
+        dDq_dwb.block<3,1>(0,i) = R2v( q_in_1.matrix().transpose() * q_in_2.matrix())/ddelta_bias2;
+    }
+
+    ASSERT_TRUE((dDq_dwb - bias_jac2.dDq_dwb_).isMuchSmallerThan(1,0.001)) << "dDq_dwb : \n" << dDq_dwb << "\n bias_jac2.dDq_dwb_ :\n" << bias_jac2.dDq_dwb_ <<
+     "\ndDq_dwb_a - dDq_dwb_ : \n" << bias_jac2.dDq_dwb_ - dDq_dwb << "\n R1^T * R2 : \n"  << q_in_1.matrix().transpose() * q_in_2.matrix() << std::endl;
+}
+
+                                ///Perturbation TESTS
+
+/* reminder : 
+                            jacobian_delta_preint_vect_                                                            jacobian_delta_vect_
+                            0: + 0,                                                                                 0: + 0
+                            1: +dPx, 2: +dPy, 3: +dPz                                                               1: + dpx, 2: +dpy, 3: +dpz
+                            4: +dOx, 5: +dOy, 6: +dOz                                                               4: + dox, 5: +doy, 6: +doz
+                            7: +dVx, 8: +dVy, 9: +dVz                                                               7: + dvx, 8: +dvy, 9: +dvz
+*/
+
+/*              Numerical method to check jacobians wrt noise
+
+                                                            dDp_dP = [dDp_dPx, dDp_dPy, dDp_dPz]
+    dDp_dPx = ((P + dPx) - P)/dPx = Id
+    dDp_dPy = ((P + dPy) - P)/dPy = Id
+    dDp_dPz = ((P + dPz) - P)/dPz = Id
+
+                                                            dDp_dV = [dDp_dVx, dDp_dVy, dDp_dVz]
+    dDp_dVx = ((V + dVx)*dt - V*dt)/dVx = Id*dt
+    dDp_dVy = ((V + dVy)*dt - V*dt)/dVy = Id*dt
+    dDp_dVz = ((V + dVz)*dt - V*dt)/dVz = Id*dt
+
+                                                            dDp_dO = [dDp_dOx, dDp_dOy, dDp_dOz]
+    dDp_dOx = (( dR(Theta + dThetax)*dp ) - ( dR(Theta)*dp ))/dThetax 
+            = (( dR(Theta) * exp(dThetax,0,0)*dp ) - ( dR(Theta)*dp ))/dThetax
+    dDp_dOy = (( dR(Theta) * exp(0,dThetay,0)*dp ) - ( dR(Theta)*dp ))/dThetay
+    dDp_dOz = (( dR(Theta) * exp(0,0,dThetaz)*dp ) - ( dR(Theta)*dp ))/dThetaz
+
+                                                            dDv_dP = [dDv_dPx, dDv_dPy, dDv_dPz] = [0, 0, 0]
+
+                                                            dDv_dV = [dDv_dVx, dDv_dVy, dDv_dVz]
+    dDv_dVx = ((V + dVx) - V)/dVx = Id
+    dDv_dVy = ((V + dVy) - V)/dVy = Id
+    dDv_dVz = ((V + dVz) - V)/dVz = Id
+    
+                                                            dDv_dO = [dDv_dOx, dDv_dOy, dDv_dOz]
+    dDv_dOx = (( dR(Theta + dThetax)*dv ) - ( dR(Theta)*dv ))/dThetax 
+            = (( dR(Theta) * exp(dThetax,0,0)*dv ) - ( dR(Theta)*dv ))/dThetax
+    dDv_dOx = (( dR(Theta) * exp(0,dThetay,0)*dv ) - ( dR(Theta)*dv ))/dThetay
+    dDv_dOz = (( dR(Theta) * exp(0,0,dThetaz)*dv ) - ( dR(Theta)*dv ))/dThetaz
+
+                                                            dDp_dp = [dDp_dpx, dDp_dpy, dDp_dpz]
+    dDp_dpx = ( dR*(p + dpx) - dR*(p))/dpx
+    dDp_dpy = ( dR*(p + dpy) - dR*(p))/dpy
+    dDp_dpz = ( dR*(p + dpz) - dR*(p))/dpy
+
+                                                            dDp_dv = [dDp_dvx, dDp_dvy, dDp_dvz] = [0, 0, 0]
+    
+                                                            dDp_do = [dDp_dox, dDp_doy, dDp_doz] = [0, 0, 0]
+
+                                                            dDv_dp = [dDv_dpx, dDv_dpy, dDv_dpz] = [0, 0, 0]
+                                                            
+                                                            dDv_dv = [dDv_dvx, dDv_dvy, dDv_dvz]
+    dDv_dvx = ( dR*(v + dvx) - dR*(v))/dvx
+    dDv_dvy = ( dR*(v + dvy) - dR*(v))/dvy
+    dDv_dvz = ( dR*(v + dvz) - dR*(v))/dvz
+
+                                                            dDv_do = [dDv_dox, dDv_doy, dDv_doz] = [0, 0, 0]
+
+                                                            dDo_dp = dDo_dv = dDo_dP = dDo_dV = [0, 0, 0]
+
+                                                            dDo_dO = [dDo_dOx, dDo_dOy, dDo_dOz]
+                                                            
+    dDo_dOx = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta+dThetax) * dr(theta) )/dThetax
+            = log( (dR(Theta) * dr(theta)).transpose() * (dR(Theta)*exp(dThetax,0,0)) * dr(theta) )/dThetax
+            = log( (_Delta * _delta).transpose() * (_Delta_noisy * _delta))
+    dDo_dOy = log( (dR(Theta) * dr(theta)).transpose() * (dR(Theta)*exp(0,dThetay,0)) * dr(theta) )/dThetay
+    dDo_dOz = log( (dR(Theta) * dr(theta)).transpose() * (dR(Theta)*exp(0,0,dThetaz)) * dr(theta) )/dThetaz
+
+                                                            dDo_do = [dDo_dox, dDo_doy, dDo_doz]
+
+    dDo_dox = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta) * dr(theta+dthetax) )/dthetax
+            = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta) * (dr(theta)*exp(dthetax,0,0)) )/dthetax
+            = log( (_Delta * _delta).transpose() * (_Delta * _delta_noisy))
+    dDo_doy = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta) * (dr(theta)*exp(0,dthetay,0)) )/dthetay
+    dDo_doz = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta) * (dr(theta)*exp(0,0,dthetaz)) )/dthetaz
+     */
+     
+TEST_F(ProcessorIMU_jacobians, dDp_dP)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDp_dP;
+
+    //dDp_dPx = ((P + dPx) - P)/dPx
+    for(int i=0;i<3;i++)
+        dDp_dP.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i).head(3) - deltas_jac.Delta0_.head(3))/Delta_noise(i);
+
+    ASSERT_TRUE((dDp_dP - deltas_jac.jacobian_delta_preint_.block(0,0,3,3)).isMuchSmallerThan(1,0.000001)) << "dDp_dP : \n" << dDp_dP << "\n deltas_jac.jacobian_delta_preint_.block(0,0,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,0,3,3) <<
+     "\ndDp_dP_a - dDp_dP_ : \n" << deltas_jac.jacobian_delta_preint_.block(0,0,3,3) - dDp_dP << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDp_dV)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDp_dV;
+
+    //Dp_dVx = ((V + dVx)*dt - V*dt)/dVx
+    for(int i=0;i<3;i++)
+        dDp_dV.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i+6).tail(3)*dt - deltas_jac.Delta0_.tail(3)*dt)/Delta_noise(i+6);
+
+    ASSERT_TRUE((dDp_dV - deltas_jac.jacobian_delta_preint_.block(0,6,3,3)).isMuchSmallerThan(1,0.000001)) << "dDp_dV : \n" << dDp_dV << "\n deltas_jac.jacobian_delta_preint_.block(0,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,6,3,3) <<
+     "\ndDp_dV_a - dDp_dV_ : \n" << deltas_jac.jacobian_delta_preint_.block(0,6,3,3) - dDp_dV << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDp_dO)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> Dq0(NULL), dq0(NULL), Dq_noisy(NULL), dq_noisy(NULL);
+    Eigen::Matrix3s dDp_dO;
+
+    //dDp_dOx = (( dR(Theta) * exp(dThetax,0,0)*dp ) - ( dR(Theta)*dp ))/dThetax
+    remapJacDeltas_quat0(deltas_jac, Dq0, dq0);
+    for(int i=0;i<3;i++){
+        remapJacDeltas_quat(deltas_jac, Dq_noisy, dq_noisy, i+3);
+        dDp_dO.block<3,1>(0,i) = ((Dq_noisy.matrix() * deltas_jac.delta0_.head(3)) - (Dq0.matrix()* deltas_jac.delta0_.head(3)))/Delta_noise(i+3);
+    }
+
+    ASSERT_TRUE((dDp_dO - deltas_jac.jacobian_delta_preint_.block(0,3,3,3)).isMuchSmallerThan(1,0.000001)) << "dDp_dO : \n" << dDp_dO << "\n deltas_jac.jacobian_delta_preint_.block(0,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(0,3,3,3) <<
+     "\ndDp_dO_a - dDp_dO_ : \n" << deltas_jac.jacobian_delta_preint_.block(0,3,3,3) - dDp_dO << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDv_dV)
+{
+    using namespace wolf;
+    Eigen::Matrix3s dDv_dV;
+
+    //dDv_dVx = ((V + dVx) - V)/dVx
+    for(int i=0;i<3;i++)
+        dDv_dV.block<3,1>(0,i) = (deltas_jac.Delta_noisy_vect_(i+6).tail(3) - deltas_jac.Delta0_.tail(3))/Delta_noise(i+6);
+
+    ASSERT_TRUE((dDv_dV - deltas_jac.jacobian_delta_preint_.block(6,6,3,3)).isMuchSmallerThan(1,0.000001)) << "dDv_dV : \n" << dDv_dV << "\n deltas_jac.jacobian_delta_preint_.block(6,6,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(6,6,3,3) <<
+     "\ndDv_dV_a - dDv_dV_ : \n" << deltas_jac.jacobian_delta_preint_.block(6,6,3,3) - dDv_dV << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDv_dO)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> Dq0(NULL), dq0(NULL), Dq_noisy(NULL), dq_noisy(NULL);
+    Eigen::Matrix3s dDv_dO;
+
+    //dDv_dOx = (( dR(Theta) * exp(dThetax,0,0)*dv ) - ( dR(Theta)*dv ))/dThetax
+    remapJacDeltas_quat0(deltas_jac, Dq0, dq0);
+    for(int i=0;i<3;i++){
+        remapJacDeltas_quat(deltas_jac, Dq_noisy, dq_noisy, i+3);
+        dDv_dO.block<3,1>(0,i) = ((Dq_noisy.matrix() * deltas_jac.delta0_.tail(3)) - (Dq0.matrix()* deltas_jac.delta0_.tail(3)))/Delta_noise(i+3);
+    }
+
+    ASSERT_TRUE((dDv_dO - deltas_jac.jacobian_delta_preint_.block(6,3,3,3)).isMuchSmallerThan(1,0.000001)) << "dDv_dO : \n" << dDv_dO << "\n deltas_jac.jacobian_delta_preint_.block(6,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(6,3,3,3) <<
+     "\ndDv_dO_a - dDv_dO_ : \n" << deltas_jac.jacobian_delta_preint_.block(6,3,3,3) - dDv_dO << std::endl;
+}
+
+//dDo_dP = dDo_dV = [0, 0, 0]
+
+
+TEST_F(ProcessorIMU_jacobians, dDo_dO)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> Dq0(NULL), dq0(NULL), Dq_noisy(NULL), dq_noisy(NULL);
+    Eigen::Matrix3s dDo_dO;
+
+    //dDo_dOx = log( (dR(Theta) * dr(theta)).transpose() * (dR(Theta)*exp(dThetax,0,0)) * dr(theta) )/dThetax
+    remapJacDeltas_quat0(deltas_jac, Dq0, dq0);
+    for(int i=0;i<3;i++){
+        remapJacDeltas_quat(deltas_jac, Dq_noisy, dq_noisy, i+3);
+        dDo_dO.block<3,1>(0,i) = R2v( (Dq0.matrix() * dq0.matrix()).transpose() * (Dq_noisy.matrix() * dq0.matrix()) )/Delta_noise(i+3);
+    }
+
+    ASSERT_TRUE((dDo_dO - deltas_jac.jacobian_delta_preint_.block(3,3,3,3)).isMuchSmallerThan(1,0.000001)) << "dDo_dO : \n" << dDo_dO << "\n deltas_jac.jacobian_delta_preint_.block(3,3,3,3) :\n" << deltas_jac.jacobian_delta_preint_.block(3,3,3,3) <<
+     "\ndDo_dO_a - dDo_dO_ : \n" << deltas_jac.jacobian_delta_preint_.block(3,3,3,3) - dDo_dO << std::endl;
+}
+
+TEST_F(ProcessorIMU_jacobians, dDp_dp)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> Dq0(NULL), dq0(NULL);
+    Eigen::Matrix3s dDp_dp, dDp_dp_a;
+
+    dDp_dp_a = deltas_jac.jacobian_delta_.block(0,0,3,3);
+    remapJacDeltas_quat0(deltas_jac, Dq0, dq0);
+    //dDp_dpx = ( dR*(p + dpx) - dR*(p))/dpx
+    for(int i=0;i<3;i++)
+        dDp_dp.block<3,1>(0,i) = ( (Dq0.matrix() * deltas_jac.delta_noisy_vect_(i).head(3)) - (Dq0.matrix() * deltas_jac.delta0_.head(3)) )/delta_noise(i);
+
+    ASSERT_TRUE((dDp_dp - dDp_dp_a).isMuchSmallerThan(1,0.000001)) << "dDp_dp : \n" << dDp_dp << "\n dDp_dp_a :\n" << dDp_dp_a <<
+     "\ndDp_dp_a - dDp_dp_ : \n" << dDp_dp_a - dDp_dp << std::endl;
+}
+
+//dDv_dp = [0, 0, 0]
+
+
+TEST_F(ProcessorIMU_jacobians, dDv_dv)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> Dq0(NULL), dq0(NULL);
+    Eigen::Matrix3s dDv_dv, dDv_dv_a;
+
+    dDv_dv_a = deltas_jac.jacobian_delta_.block(6,6,3,3);
+    remapJacDeltas_quat0(deltas_jac, Dq0, dq0);
+    //dDv_dvx = ( dR*(v + dvx) - dR*(v))/dvx
+    for(int i=0;i<3;i++)
+        dDv_dv.block<3,1>(0,i) = ( (Dq0 * deltas_jac.delta_noisy_vect_(i+6).tail(3)) - (Dq0 * deltas_jac.delta0_.tail(3)) )/delta_noise(i+6);
+
+    ASSERT_TRUE((dDv_dv - dDv_dv_a).isMuchSmallerThan(1,0.000001)) << "dDv_dv : \n" << dDv_dv << "\n dDv_dv_a :\n" << dDv_dv_a <<
+     "\ndDv_dv_a - dDv_dv_ : \n" << dDv_dv_a - dDv_dv << std::endl;
+}
+
+//dDo_dp = dDo_dv = [0, 0, 0]
+
+TEST_F(ProcessorIMU_jacobians, dDo_do)
+{
+    using namespace wolf;
+    Eigen::Map<Eigen::Quaternions> Dq0(NULL), dq0(NULL), Dq_noisy(NULL), dq_noisy(NULL);
+    Eigen::Matrix3s dDo_do, dDo_do_a;
+
+    //dDo_dox = log( (dR(Theta) * dr(theta)).transpose() * dR(Theta) * (dr(theta)*exp(dthetax,0,0)) )/dthetax
+    remapJacDeltas_quat0(deltas_jac, Dq0, dq0);
+    dDo_do_a = deltas_jac.jacobian_delta_.block(3,3,3,3);
+
+    for(int i=0;i<3;i++){
+        remapJacDeltas_quat(deltas_jac, Dq_noisy, dq_noisy, i+3);
+        dDo_do.block<3,1>(0,i) = R2v( (Dq0.matrix() * dq0.matrix()).transpose() * (Dq0.matrix() * dq_noisy.matrix()) )/Delta_noise(i+3);
+    }
+
+    ASSERT_TRUE((dDo_do - dDo_do_a).isMuchSmallerThan(1,0.000001)) << "dDo_do : \n" << dDo_do << "\n dDo_do_a :\n" << dDo_do_a <<
+     "\ndDo_do_a - dDo_do_ : \n" << dDo_do_a - dDo_do << std::endl;
+}
+
+
+int main(int argc, char **argv)
+{
+    using namespace wolf;
+
+     testing::InitGoogleTest(&argc, argv);
+     return RUN_ALL_TESTS();
+}
\ No newline at end of file
diff --git a/src/test/gtest_processorMotion_optimization_testCase.cpp b/src/test/gtest_processorMotion_optimization_testCase.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..90937271473af6e4a5d01876627a0b66a1109e33
--- /dev/null
+++ b/src/test/gtest_processorMotion_optimization_testCase.cpp
@@ -0,0 +1,6698 @@
+/**
+ * \file gtest_processorMotion_optimisation_testCase.cpp
+ *
+ *  Created on: Jan 18, 2017
+ *      \author: Dinesh Atchuthan
+ */
+
+
+#include "utils_gtest.h"
+
+#include "wolf.h"
+#include "logging.h"
+
+#include "processor_odom_3D.h"
+#include "processor_imu.h"
+#include "wolf.h"
+#include "problem.h"
+#include "ceres_wrapper/ceres_manager.h"
+#include "state_quaternion.h"
+#include "sensor_imu.h"
+#include "rotations.h"
+
+// wolf yaml
+#include "../yaml/yaml_conversion.h"
+// yaml-cpp library
+#include <../yaml-cpp/yaml.h>
+
+#include <iostream>
+#include <fstream>
+
+using namespace Eigen;
+using namespace std;
+using namespace wolf;
+
+//Global variables
+
+//used in pure_translation test
+char * filename_motion_imu_data;
+char * filename_motion_odom;
+unsigned int number_of_KF = 2; //determine the number of final keyframes that will be created (except origin, so n>=1) in some of processorIMU tests
+
+class ProcessorIMU_Odom_tests : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        Eigen::Vector6s data_;
+        wolf::Scalar dt;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        //===================================================== SETTING PROBLEM
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        ASSERT_TRUE(number_of_KF>0) << "number_of_KF (number of Keyframe created) must be int >0";
+
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs x0(16);
+        x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,.00,  0,0,.00;
+        t.set(0);
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+
+        // SENSOR + PROCESSOR IMU
+        //We want a processorIMU with a specific max_time_span (1s) forour test
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+        prc_imu_params->max_time_span = 1;
+        prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_imu_params->dist_traveled = 1000000000;
+        prc_imu_params->angle_turned = 1000000000;
+
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+        //ORIGIN MUST BE SET IN THE TEST
+
+    //===================================================== END{SETTING PROBLEM}
+    }
+
+    virtual void TearDown()
+    {
+        // code here will be called just after the test completes
+        // ok to through exceptions from here if need be
+        /*
+            You can do deallocation of resources in TearDown or the destructor routine. 
+                However, if you want exception handling you must do it only in the TearDown code because throwing an exception 
+                from the destructor results in undefined behavior.
+            The Google assertion macros may throw exceptions in platforms where they are enabled in future releases. 
+                Therefore, it's a good idea to use assertion macros in the TearDown code for better maintenance.
+        */
+    }
+};
+
+class ProcessorIMU_Odom_tests_details : public testing::Test
+{
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving and we add an odometry and IMU constraint.
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1
+     *     \____constraintOdom3D___/
+     */
+
+    public:
+
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        Eigen::VectorXs initial_origin_state;
+        Eigen::VectorXs initial_final_state;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        std::vector<StateBlockPtr> originStateBlock_vec;
+        std::vector<StateBlockPtr> finalStateBlock_vec;
+        std::vector<StateBlockPtr> allStateBlocks;
+        Eigen::VectorXs perturbated_origin_state;
+        Eigen::VectorXs perturbated_final_state;
+        ceres::Solver::Summary summary;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        //===================================================== SETTING PROBLEM
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        ASSERT_TRUE(number_of_KF>0) << "number_of_KF (number of Keyframe created) must be int >0";
+
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs x0(16);
+        x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,.00,  0,0,.00;
+        TimeStamp t(0);
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+
+        // SENSOR + PROCESSOR IMU
+        //We want a processorIMU with a specific max_time_span (1s) forour test
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+        prc_imu_params->max_time_span = 1;
+        prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_imu_params->dist_traveled = 1000000000;
+        prc_imu_params->angle_turned = 1000000000;
+        prc_imu_params->voting_active = true;
+
+        ProcessorBasePtr processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+        SensorIMUPtr sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        ProcessorIMUPtr processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        SensorOdom3DPtr sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        ProcessorOdom3DPtr processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+        //set processorMotions
+        FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x0, t);
+        processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+        wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+        //There should be 3 captures at origin_frame : CaptureOdom, captureIMU
+        EXPECT_EQ((wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front())->getCaptureList().size(),2);
+        ASSERT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isKey()) << "origin_frame is not a KeyFrame..." << std::endl;
+
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS IMU DATA
+
+        Eigen::Vector6s data;
+        data << 0.00, 0.000, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+        Scalar dt = t.get();
+        TimeStamp ts(0.001);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+        while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()) ){
+        
+            // Time and data variables
+            dt += 0.001;
+            ts.set(dt);
+            imu_ptr->setTimeStamp(ts);
+        	imu_ptr->setData(data);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+        }
+
+        // PROCESS ODOM 3D DATA
+        Eigen::Vector6s data_odom3D;
+        data_odom3D << 0,0,0, 0,0,0;
+    
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+        sen_odom3D->process(mot_ptr);
+
+        //===================================================== END{PROCESS DATA}
+
+        //===================================================== TESTS PREPARATION
+
+        origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+        initial_origin_state.resize(16);
+        initial_final_state.resize(16);
+        perturbated_origin_state.resize(16);
+        perturbated_final_state.resize(16);
+
+        //store states before optimization so that we can reset the frames to their original state for other optimization tests
+        origin_KF->getState(initial_origin_state);
+        last_KF->getState(initial_final_state);
+
+        //get stateblocks from origin and last KF and concatenate them in one std::vector to unfix stateblocks
+        originStateBlock_vec = origin_KF->getStateBlockVec();
+        finalStateBlock_vec = last_KF->getStateBlockVec();
+
+        allStateBlocks.reserve(originStateBlock_vec.size() + finalStateBlock_vec.size());
+        allStateBlocks.insert( allStateBlocks.end(), originStateBlock_vec.begin(), originStateBlock_vec.end() );
+        allStateBlocks.insert( allStateBlocks.end(), finalStateBlock_vec.begin(), finalStateBlock_vec.end() );
+
+        //===================================================== END{TESTS PREPARATION}
+    }
+
+    virtual void TearDown(){}
+};
+
+
+class ProcessorIMU_Odom_tests_details3KF : public testing::Test
+{
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving and we add an odometry and IMU constraint.
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1
+     *     \____constraintOdom3D___/
+     */
+
+    public:
+
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        Eigen::VectorXs initial_origin_state;
+        Eigen::VectorXs initial_final_state;
+        Eigen::VectorXs initial_middle_state;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr middle_KF;
+        FrameIMUPtr last_KF;
+        std::vector<StateBlockPtr> originStateBlock_vec;
+        std::vector<StateBlockPtr> middleStateBlock_vec;
+        std::vector<StateBlockPtr> finalStateBlock_vec;
+        std::vector<StateBlockPtr> allStateBlocks;
+        Eigen::VectorXs perturbated_origin_state;
+        Eigen::VectorXs perturbated_middle_state;
+        Eigen::VectorXs perturbated_final_state;
+        ceres::Solver::Summary summary;
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        //===================================================== SETTING PROBLEM
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        ASSERT_TRUE(number_of_KF>0) << "number_of_KF (number of Keyframe created) must be int >0";
+
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs x0(16);
+        x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,.00,  0,0,.00;
+        TimeStamp t(0);
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+
+        // SENSOR + PROCESSOR IMU
+        //We want a processorIMU with a specific max_time_span (1s) forour test
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+        prc_imu_params->max_time_span = 1;
+        prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_imu_params->dist_traveled = 1000000000;
+        prc_imu_params->angle_turned = 1000000000;
+        prc_imu_params->voting_active = true;
+
+        ProcessorBasePtr processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+        SensorIMUPtr sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        ProcessorIMUPtr processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 1;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        SensorOdom3DPtr sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        ProcessorOdom3DPtr processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+        //set processorMotions
+        FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x0, t);
+        processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+        wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+        //There should be 3 captures at origin_frame : CaptureOdom, captureIMU
+        EXPECT_EQ((wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front())->getCaptureList().size(),2);
+        ASSERT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isKey()) << "origin_frame is not a KeyFrame..." << std::endl;
+
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS IMU DATA
+
+        Eigen::Vector6s data;
+        data << 0.00, 0.000, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+        Scalar dt = t.get();
+        TimeStamp ts(0.001);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+        while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()*2) ){
+        
+            // Time and data variables
+            dt += 0.001;
+            ts.set(dt);
+            imu_ptr->setTimeStamp(ts);
+        	imu_ptr->setData(data);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == 1 || ts.get() == 2)
+            {
+                // PROCESS ODOM 3D DATA
+                Eigen::Vector6s data_odom3D;
+                data_odom3D << 0,0,0, 0,0,0;
+    
+                wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+                sen_odom3D->process(mot_ptr);
+            }
+        }
+
+        //===================================================== END{PROCESS DATA}
+
+        //===================================================== TESTS PREPARATION
+        wolf::TimeStamp middle_ts(1);
+
+        origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+        middle_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(middle_ts));
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+        initial_origin_state.resize(16);
+        initial_middle_state.resize(16);
+        initial_final_state.resize(16);
+        perturbated_origin_state.resize(16);
+        perturbated_middle_state.resize(16);
+        perturbated_final_state.resize(16);
+
+        //store states before optimization so that we can reset the frames to their original state for other optimization tests
+        origin_KF->getState(initial_origin_state);
+        middle_KF->getState(initial_middle_state);
+        last_KF->getState(initial_final_state);
+
+        //get stateblocks from origin and last KF and concatenate them in one std::vector to unfix stateblocks
+        originStateBlock_vec = origin_KF->getStateBlockVec();
+        middleStateBlock_vec = middle_KF->getStateBlockVec();
+        finalStateBlock_vec = last_KF->getStateBlockVec();
+
+        allStateBlocks.reserve(originStateBlock_vec.size() + finalStateBlock_vec.size() + middleStateBlock_vec.size());
+        allStateBlocks.insert( allStateBlocks.end(), originStateBlock_vec.begin(), originStateBlock_vec.end() );
+        allStateBlocks.insert( allStateBlocks.end(), middleStateBlock_vec.begin(), middleStateBlock_vec.end() );
+        allStateBlocks.insert( allStateBlocks.end(), finalStateBlock_vec.begin(), finalStateBlock_vec.end() );
+
+        //===================================================== END{TESTS PREPARATION}
+    }
+
+    virtual void TearDown(){}
+};
+
+
+class ProcessorIMU_Odom_tests_plateform_simulation : public testing::Test
+{
+    public:
+        wolf::TimeStamp t;
+        Eigen::Vector6s data_;
+        wolf::Scalar dt;
+        SensorIMUPtr sen_imu;
+        SensorOdom3DPtr sen_odom3D;
+        ProblemPtr wolf_problem_ptr_;
+        CeresManager* ceres_manager_wolf_diff;
+        ProcessorBasePtr processor_ptr_;
+        ProcessorIMUPtr processor_ptr_imu;
+        ProcessorOdom3DPtr processor_ptr_odom3D;
+        FrameIMUPtr origin_KF;
+        FrameIMUPtr last_KF;
+        Eigen::Matrix<wolf::Scalar, 10, 1> expected_final_state;
+
+
+
+    virtual void SetUp()
+    {
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+
+        //===================================================== SETTING PROBLEM
+        std::string wolf_root = _WOLF_ROOT_DIR;
+        ASSERT_TRUE(number_of_KF>0) << "number_of_KF (number of Keyframe created) must be int >0";
+
+        // WOLF PROBLEM
+        wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+        Eigen::VectorXs x0(16);
+        x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,.00,  0,0,.00;
+        t.set(0);
+
+        // CERES WRAPPER
+        ceres::Solver::Options ceres_options;
+        ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+        ceres_options.max_line_search_step_contraction = 1e-3;
+        ceres_options.max_num_iterations = 1e4;
+        ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+
+        // SENSOR + PROCESSOR IMU
+        //We want a processorIMU with a specific max_time_span (1s) forour test
+        SensorBasePtr sen0_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+        prc_imu_params->max_time_span = 1;
+        prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_imu_params->dist_traveled = 1000000000;
+        prc_imu_params->angle_turned = 1000000000;
+
+        processor_ptr_ = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen0_ptr, prc_imu_params);
+        sen_imu = std::static_pointer_cast<SensorIMU>(sen0_ptr);
+        processor_ptr_imu = std::static_pointer_cast<ProcessorIMU>(processor_ptr_);
+
+
+        // SENSOR + PROCESSOR ODOM 3D
+        SensorBasePtr sen1_ptr = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+        ProcessorOdom3DParamsPtr prc_odom3D_params = std::make_shared<ProcessorOdom3DParams>();
+        prc_odom3D_params->max_time_span = 0.99;
+        prc_odom3D_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+        prc_odom3D_params->dist_traveled = 1000000000;
+        prc_odom3D_params->angle_turned = 1000000000;
+
+        ProcessorBasePtr processor_ptr_odom = wolf_problem_ptr_->installProcessor("ODOM 3D", "odom", sen1_ptr, prc_odom3D_params);
+        sen_odom3D = std::static_pointer_cast<SensorOdom3D>(sen1_ptr);
+        processor_ptr_odom3D = std::static_pointer_cast<ProcessorOdom3D>(processor_ptr_odom);
+
+        //ORIGIN MUST BE SET IN THE TEST
+
+    //===================================================== END{SETTING PROBLEM}
+
+        char* imu_filepath;
+        char* odom_filepath;
+        std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/data_trajectory_full.txt");
+        std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_trajectory_full.txt");
+        imu_filepath   = new char[imu_filepath_string.length() + 1];
+        odom_filepath   = new char[odom_filepath_string.length() + 1];
+        std::strcpy(imu_filepath, imu_filepath_string.c_str());
+        std::strcpy(odom_filepath, odom_filepath_string.c_str());
+        std::ifstream imu_data_input;
+        std::ifstream odom_data_input;
+
+        imu_data_input.open(imu_filepath);
+        odom_data_input.open(odom_filepath);
+        //WOLF_INFO("imu file: ", imu_filepath)
+        if(!imu_data_input.is_open() | !odom_data_input.is_open()){
+            std::cerr << "Failed to open data files... Exiting" << std::endl;
+            ADD_FAILURE();
+        }
+
+        //===================================================== SETTING PROBLEM
+
+        // reset origin of problem
+        Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+        // initial conditions defined from data file
+        // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+        imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+        t.set(0);
+        origin_KF = std::static_pointer_cast<FrameIMU>(processor_ptr_imu->setOrigin(x_origin, t));
+        processor_ptr_odom3D->setOrigin(origin_KF);
+
+        odom_data_input >> expected_final_state[0] >> expected_final_state[1] >> expected_final_state[2] >> expected_final_state[6] >> expected_final_state[3] >>
+                             expected_final_state[4] >> expected_final_state[5] >> expected_final_state[7] >> expected_final_state[8] >> expected_final_state[9];
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+        Eigen::Vector6s data_imu, data_odom3D;
+        data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+        data_odom3D << 0,0,0, 0,0,0;
+
+        Scalar input_clock;
+        TimeStamp ts(0);
+        TimeStamp t_odom(0);
+        wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+        wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+        //read first odom data from file
+        odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+        t_odom.set(input_clock);
+        //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+        while( !imu_data_input.eof() && !odom_data_input.eof() )
+        {
+            // PROCESS IMU DATA
+            // Time and data variables
+            imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+            ts.set(input_clock);
+            imu_ptr->setTimeStamp(ts);
+            imu_ptr->setData(data_imu);
+
+            // process data in capture
+            imu_ptr->getTimeStamp();
+            sen_imu->process(imu_ptr);
+
+            if(ts.get() == t_odom.get()) //every 100 ms
+            {
+                // PROCESS ODOM 3D DATA
+                mot_ptr->setTimeStamp(t_odom);
+                mot_ptr->setData(data_odom3D);
+                sen_odom3D->process(mot_ptr);
+
+                //prepare next odometry measurement if there is any
+                odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+                t_odom.set(input_clock);
+            }
+        }
+
+        last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+        //closing file
+        imu_data_input.close();
+        odom_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+    }
+
+    virtual void TearDown(){}
+};
+
+TEST(ProcessorOdom3D, static_ceresOptimisation_Odom_PO)
+{
+
+    /* Simple odom test including only processorOdom3D :
+     * First keyFrame (origin) is fixed (0,0,0, 0,0,0,1). Then the odometry data for 2 second is [0,0,0, 0,0,0,1], meaning that we did not move at all. 
+     * We give this simple graph to solver and let it solve.
+     * Everything should converge and final keyFrame State should be exactly [0,0,0, 0,0,0,1]
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+                                            /************** SETTING PROBLEM  **************/
+
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // Wolf problem
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PO 3D");
+
+    SensorBasePtr sen = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+
+    // We want to create a processorMotion with a max_time_span of 2 seconds. but here we integrate only odometry and there should be no interpolation between
+    // Default processorMotionParams is made so that a KeyFrame will be created at each step. This works in this case
+    ProcessorOdom3DParamsPtr prc_odom_params = std::make_shared<ProcessorOdom3DParams>();
+    wolf_problem_ptr_->installProcessor("ODOM 3D", "odometry integrator", sen, prc_odom_params);
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin((Vector7s()<<0,0,0,0,0,0,1).finished(), TimeStamp(0));
+
+    // Ceres wrappers
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+                                             /************** USE ODOM_3D CLASSES  **************/
+
+    VectorXs d(7);
+    d << 0,0,0, 0,0,0,1;
+    TimeStamp t(2);
+
+    wolf::CaptureMotionPtr odom_ptr = std::make_shared<CaptureMotion>(t, sen, d, 7, 6);
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+    // process data in capture
+    sen->process(odom_ptr);
+
+    /* We do not need to create features and frames and constraints here. Everything is done in wolf.
+    Features and constraint at created automatically when a new Keyframe is generated. Whether a new keyframe should be created or not, this is
+    handled by voteForKeyFrame() function for this processorMotion
+    */
+                                             /************** SOLVER PART  **************/
+     ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+     //There should be 3 frames : origin KeyFrame, Generated KeyFrame at t = 2s, and another Frame for incoming data to be processed
+     ASSERT_EQ(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().size(),3);
+     
+     //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+     ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different" << std::endl;
+     ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different" << std::endl;
+     EXPECT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isFixed()) << "origin_frame is not fixed" << std::endl;
+}
+
+TEST(ProcessorOdom3D, static_ceresOptimisation_convergenceOdom_PO)
+{
+
+    /* Simple odom test including only processorOdom3D :
+     * First keyFrame (origin) is fixed (0,0,0, 0,0,0,1). Then the odometry data for 2 second is [0,0,0, 0,0,0,1], meaning that we did not move at all. 
+     * We give this simple graph to solver and let it solve. 
+     *
+     * But before solving, we change the state of final KeyFrame.
+     * First we change only Px, then Py, then Pz, then all of them
+     * Second : we change Ox, then Oy, then Oz, then all of them
+     * Third : we change everything
+     * Everything should converge and final keyFrame State should be exactly [0,0,0, 0,0,0,1]
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+                                            /************** SETTING PROBLEM  **************/
+
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // Wolf problem
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PO 3D");
+
+    SensorBasePtr sen = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+
+    // We want to create a processorMotion with a max_time_span of 2 seconds. but here we integrate only odometry and there should be no interpolation between
+    // Default processorMotionParams is made so that a KeyFrame will be created at each step. This works in this case
+    ProcessorOdom3DParamsPtr prc_odom_params = std::make_shared<ProcessorOdom3DParams>();
+    wolf_problem_ptr_->installProcessor("ODOM 3D", "odometry integrator", sen, prc_odom_params);
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin((Vector7s()<<0,0,0,0,0,0,1).finished(), TimeStamp(0));
+
+    // Ceres wrappers
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+                                             /************** USE ODOM_3D CLASSES  **************/
+
+    VectorXs d(7);
+    d << 0,0,0, 0,0,0,1;
+    TimeStamp t(2);
+
+    wolf::CaptureMotionPtr odom_ptr = std::make_shared<CaptureMotion>(t, sen, d, 7, 6);
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+    // process data in capture
+    sen->process(odom_ptr);
+
+                                             /************** SOLVER PART  **************/
+
+     /* ___________________________________________ CHANGING FINAL FRAME BEFORE OPTIMIZATION ___________________________________________*/
+    
+    //There should be 3 frames : origin KeyFrame, Generated KeyFrame at t = 2s, and another Frame for incoming data to be processed
+    ASSERT_EQ(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().size(),3);
+    EXPECT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isFixed()) << "origin_frame is not fixed" << std::endl;
+
+    //get pointer to the last KeyFrame (which is at t = 2s)
+    EXPECT_EQ(t.get(),2);
+    FrameBasePtr last_KF = wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t);
+
+    // FIRST SOLVER TEST WITHOUT CHANGING ANYTHING - WE DID NOT MOVE
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different" << std::endl;
+    
+
+                                                    /*********************/
+                                                    //CHANGE PX AND SOLVE//
+                                                    /*********************/
+
+    last_KF->setState((Vector7s()<<30,0,0,0,0,0,1).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Px is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Px is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE PY AND SOLVE//
+                                                    /*********************/
+
+    last_KF->setState((Vector7s()<<0,30,0,0,0,0,1).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Py is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Py is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE PZ AND SOLVE//
+                                                    /*********************/
+
+    last_KF->setState((Vector7s()<<0,0,30,0,0,0,1).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Pz is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Pz is changed" << std::endl;
+
+
+                                                    /********************************/
+                                                    //CHANGE PX, Py AND PZ AND SOLVE//
+                                                    /********************************/
+
+    last_KF->setState((Vector7s()<<25,20,30,0,0,0,1).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Px, Py and Pz are changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Px, Py and Pz are changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE OX AND SOLVE//
+                                                    /*********************/
+    Eigen::Vector3s o_initial_guess;
+    Eigen::Quaternions q_init_guess;
+
+    o_initial_guess << 40,0,0;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,7,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w()).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Ox is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Ox is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE OY AND SOLVE//
+                                                    /*********************/
+    o_initial_guess << 0,40,0;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,7,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w()).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Oy is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Oy is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE OZ AND SOLVE//
+                                                    /*********************/
+    o_initial_guess << 0,0,40;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,7,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w()).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Oz is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Oz is changed" << std::endl;
+
+
+                                                    /********************************/
+                                                    //CHANGE OX, OY AND OZ AND SOLVE//
+                                                    /********************************/
+    o_initial_guess << 80,50,40;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,7,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w()).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Ox, Oy and Oz changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().back()->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Ox, Oy and Oz changed" << std::endl;
+}
+
+
+TEST(ProcessorOdom3D, static_ceresOptimisation_convergenceOdom_POV)
+{
+
+    /* Simple odom test including only processorOdom3D :
+     * First keyFrame (origin) is fixed (0,0,0, 0,0,0,1). Then the odometry data for 2 second is [0,0,0, 0,0,0,1], meaning that we did not move at all. 
+     * We give this simple graph to solver and let it solve. 
+     *
+     * But before solving, we change the state of final KeyFrame.
+     * First we change only Px, then Py, then Pz, then all of them
+     * Second : we change Ox, then Oy, then Oz, then all of them
+     * Third : we change everything
+     * Everything should converge and final keyFrame State should be exactly [0,0,0, 0,0,0,1 ,0,0,0] -->Checked with Assertions
+     *
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+                                            /************** SETTING PROBLEM  **************/
+
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // Wolf problem
+    ProblemPtr wolf_problem_ptr_ = Problem::create("POV 3D");
+    Eigen::VectorXs x0(10);
+    x0 << 0,0,0,  0,0,0,1,  0,0,0;
+    TimeStamp t(0);
+    wolf_problem_ptr_->setPrior(x0, Eigen::Matrix6s::Identity() * 0.001, t);
+
+    SensorBasePtr sen = wolf_problem_ptr_->installSensor("ODOM 3D", "odom", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_odom_3D.yaml");
+
+    // We want to create a processorMotion with a max_time_span of 2 seconds. but here we integrate only odometry and there should be no interpolation between
+    // Default processorMotionParams is made so that a KeyFrame will be created at each step. This works in this case
+    ProcessorOdom3DParamsPtr prc_odom_params = std::make_shared<ProcessorOdom3DParams>();
+    wolf_problem_ptr_->installProcessor("ODOM 3D", "odometry integrator", sen, prc_odom_params);
+
+    // Ceres wrappers
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+                                             /************** USE ODOM_3D CLASSES  **************/
+
+    VectorXs d(7);
+    d << 0,0,0, 0,0,0,1;
+    t.set(2);
+
+    wolf::CaptureMotionPtr odom_ptr = std::make_shared<CaptureMotion>(t, sen, d, 7, 6);
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+    // process data in capture
+    sen->process(odom_ptr);
+
+                                             /************** SOLVER PART  **************/
+
+     /* ___________________________________________ CHANGING FINAL FRAME BEFORE OPTIMIZATION ___________________________________________*/
+    
+    //There should be 3 frames : origin KeyFrame, Generated KeyFrame at t = 2s, and another Frame for incoming data to be processed
+    ASSERT_EQ(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().size(),3);
+    EXPECT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isFixed()) << "origin_frame is not fixed" << std::endl;
+
+    //get pointer to the last KeyFrame (which is at t = 2s)
+    EXPECT_EQ(t.get(),2);
+    FrameBasePtr last_KF = wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(t);
+    Eigen::Matrix<wolf::Scalar, 10, 1> kf2_state = last_KF->getState(); //This state vector will be used to get the velocity state
+
+    // FIRST SOLVER TEST WITHOUT CHANGING ANYTHING - WE DID NOT MOVE
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different" << std::endl;
+    
+
+                                                    /*********************/
+                                                    //CHANGE PX AND SOLVE//
+                                                    /*********************/
+
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<30,0,0,0,0,0,1,kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame position are different - problem when Px is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Px is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE PY AND SOLVE//
+                                                    /*********************/
+
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<0,30,0,0,0,0,1,kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame position are different - problem when Py is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Py is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE PZ AND SOLVE//
+                                                    /*********************/
+
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<0,0,30,0,0,0,1,kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame position are different - problem when Pz is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Pz is changed" << std::endl;
+
+
+                                                    /********************************/
+                                                    //CHANGE PX, Py AND PZ AND SOLVE//
+                                                    /********************************/
+
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<25,20,30,0,0,0,1,kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame position are different - problem when Px, Py and Pz are changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame orientation are different - problem when Px, Py and Pz are changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE OX AND SOLVE//
+                                                    /*********************/
+    Eigen::Vector3s o_initial_guess;
+    Eigen::Quaternions q_init_guess;
+
+    o_initial_guess << 40,0,0;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w(),kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Ox is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame orientation are different - problem when Ox is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE OY AND SOLVE//
+                                                    /*********************/
+    o_initial_guess << 0,40,0;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w(),kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Oy is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame orientation are different - problem when Oy is changed" << std::endl;
+
+
+                                                    /*********************/
+                                                    //CHANGE OZ AND SOLVE//
+                                                    /*********************/
+    o_initial_guess << 0,0,40;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w(),kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Oz is changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame orientation are different - problem when Oz is changed" << std::endl;
+
+
+                                                    /********************************/
+                                                    //CHANGE OX, OY AND OZ AND SOLVE//
+                                                    /********************************/
+    o_initial_guess << 80,50,40;
+    q_init_guess = v2q(o_initial_guess);
+    last_KF->setState((Eigen::Matrix<wolf::Scalar,10,1>()<<0,0,0,q_init_guess.x(),q_init_guess.y(),q_init_guess.z(),q_init_guess.w(),kf2_state(7),kf2_state(8),kf2_state(9)).finished());
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    //This is a static test so we are not supposed to have moved from origin to last KeyFrame
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getPPtr()->getState() - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL) ) <<
+                "origin and final frame position are different - problem when Ox, Oy and Oz changed" << std::endl;
+    ASSERT_TRUE( (wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->getOPtr()->getState() - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS) ) <<
+                "origin and final frame orientation are different - problem when Ox, Oy and Oz changed" << std::endl;
+}
+
+
+TEST(ProcessorIMU, static_ceresOptimisation_fixBias)
+{
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same
+     * Origin KeyFrame is fixed
+     * 
+     * Bias of all frames are fixed before we call the solver
+     * 
+     * With IMU data only, biases are not observable ! So covariance cannot be computed due to jacobian rank deficiency.
+     * We must add an odometry to make covariances observable Or... we could fix all bias stateBlocks
+     * First we will try to fix bias stateBlocks
+     */
+
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+                                            /************** SETTING PROBLEM  **************/
+
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // Wolf problem
+    ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D");
+
+    SensorBasePtr sen_imu = wolf_problem_ptr_->installSensor("IMU", "Main IMU", (Vector7s()<<0,0,0,0,0,0,1).finished(), wolf_root + "/src/examples/sensor_imu.yaml");
+
+    // We want to create a processorIMU with a max_time_span of 1 seconds.
+    // Default processorIMUParams is made so that a KeyFrame will be created at each step.
+    ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+    prc_imu_params->max_time_span = 1;
+    prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+    prc_imu_params->dist_traveled = 1000000000;
+    prc_imu_params->angle_turned = 1000000000;
+    prc_imu_params->voting_active = true;
+
+    ProcessorBasePtr processor_ptr = wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", sen_imu, prc_imu_params);
+
+    //setting origin and fixing origin KeyFrame
+    Eigen::VectorXs x0(16);
+    TimeStamp t(0);
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0;
+    wolf_problem_ptr_->getProcessorMotionPtr()->setOrigin(x0, t); //this also creates a keyframe at origin
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+
+    // Ceres wrappers
+    ceres::Solver::Options ceres_options;
+    ceres_options.minimizer_type = ceres::TRUST_REGION; //ceres::TRUST_REGION;ceres::LINE_SEARCH
+    ceres_options.max_line_search_step_contraction = 1e-3;
+    ceres_options.max_num_iterations = 1e4;
+    CeresManager* ceres_manager_wolf_diff = new CeresManager(wolf_problem_ptr_, ceres_options, true);
+
+                                             /************** USE IMU CLASSES  **************/
+    Eigen::Vector6s data;
+    data << 0.0,0.0,-wolf::gravity()(2), 0.0,0.0,0.0; //we use exactly the value of gravity defined in wolf.h
+
+    //integrate IMU data until KeyFrame creation (until we reach max_time_span)
+    Scalar dt = t.get();
+    TimeStamp ts(0);
+    while((dt-t.get())<=std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxTimeSpan()){
+    // Time and data variables
+    dt += 0.001;
+    ts.set(dt);
+
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+    // process data in capture
+    sen_imu->process(imu_ptr);
+    }
+
+    //Fix all biases StateBlocks -> to make covariances computable
+    for(FrameBasePtr it : wolf_problem_ptr_->getTrajectoryPtr()->getFrameList()){
+        ( std::static_pointer_cast<FrameIMU>(it) )->getAccBiasPtr()->fix();
+        ( std::static_pointer_cast<FrameIMU>(it) )->getGyroBiasPtr()->fix();
+    }
+    
+                                             /************** SOLVER PART  **************/
+     ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+     //We check with assertions if Final KeyFrame has the same state as origin_KF
+     FrameBasePtr origin_KF = wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front();
+     FrameBasePtr last_KF = wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts);
+     ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+     ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+     ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+//_______________________________________________________________________________________________________________
+// ##################################### static_Optim_IMUOdom_2KF TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+/*  Tests below will be based on the following representation :
+ *     KF0 ---- constraintIMU ---- KF1
+ *        \____constraintOdom3D___/
+ */
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_positionOrigin3_UnfixAll)
+{
+    /* Both KeyFrames are here unfixed.
+     * We perturbate all of the origin positions (Px, Py, Pz) before calling Ceres.
+     * The added odometry and IMU constraints say that we did not move between both KF. We expect CERES to converge and get the same position for both KF
+     * Since IMU constraint says that we did not move at all, we also expect the velocities to be equal in both KF.
+     * The orientation should also be the same in both KeyFrames.
+     *
+     * Finally, we expect the Acceleration and Gyroscope Bias to be equal in both KeyFrames (Zero Vector)
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(0) += 1.0;
+    perturbated_origin_state(1) += 2.0;
+    perturbated_origin_state(2) += 3.0;
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix(); 
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_positionLast3_UnfixAll)
+{
+    /* Both KeyFrames are here unfixed.
+     * We perturbate all of the final positions (Px, Py, Pz) before calling Ceres.
+     * The added odometry and IMU constraints say that we did not move between both KF. We expect CERES to converge and get the same position for both KF
+     * Since IMU constraint says that we did not move at all, we also expect the velocities to be equal in both KF.
+     * The orientation should also be the same in both KeyFrames.
+     *
+     * Finally, we expect the Acceleration and Gyroscope Bias to be equal in both KeyFrames (Zero Vector)
+     */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(0) += 1.0;
+    perturbated_final_state(1) += 2.0;
+    perturbated_final_state(2) += 3.0;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->unfix(); 
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_positionOrigin3_FixLast)
+{
+    /* origin_KF is here unfixed. last_KF is fixed.
+     * We perturbate all of the origin positions (Px, Py, Pz) before calling Ceres.
+     * The added odometry and IMU constraints say that we did not move between both KF. We expect CERES to converge and get the same position for both KF
+     * Since IMU constraint says that we did not move at all, we also expect the velocities to be equal in both KF.
+     * The orientation should also be the same in both KeyFrames.
+     *
+     * Finally, we expect the Acceleration and Gyroscope Bias to be equal in both KeyFrames (Zero Vector)
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(0) += 1.0;
+    perturbated_origin_state(1) += 2.0;
+    perturbated_origin_state(2) += 3.0;
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*0.001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_positionlast3_FixOrigin)
+{
+    /* last_KF is here unfixed. origin_KF is fixed.
+     * We perturbate all of the last positions (Px, Py, Pz) before calling Ceres.
+     * The added odometry and IMU constraints say that we did not move between both KF. We expect CERES to converge and get the same position for both KF
+     * Since IMU constraint says that we did not move at all, we also expect the velocities to be equal in both KF.
+     * The orientation should also be the same in both KeyFrames.
+     *
+     * Finally, we expect the Acceleration and Gyroscope Bias to be equal in both KeyFrames (Zero Vector)
+     */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(0) += 1.0;
+    perturbated_final_state(1) += 2.0;
+    perturbated_final_state(2) += 3.0;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->fix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*0.001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityOrigin1_Unfix1)
+{
+    /* Here we have only 1 StateBlock unfixed (Plus the velocity StateBlock from origin_KF that we perturbate)
+     * only 1 component of origin_KF velocity is perturbated here : first we perturbate Vx, then Vy and finally Vz
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    for(int pert_index = 7; pert_index<10; pert_index++)
+    {
+        //perturate initial state
+        perturbated_origin_state = initial_origin_state;
+        perturbated_origin_state(pert_index) += 1.0;
+
+        for(int i = 0; i<originStateBlock_vec.size(); i++)
+        {
+            origin_KF->setState(perturbated_origin_state);
+            last_KF->setState(initial_final_state);
+
+            origin_KF->fix();
+            last_KF->fix();
+
+            //we unfix origin velocity stateblock to let it converge
+            originStateBlock_vec[2]->unfix();
+            
+            //we now unfix one StateBlock
+            originStateBlock_vec[i]->unfix();
+
+            summary = ceres_manager_wolf_diff->solve();
+            //std::cout << summary.BriefReport() << std::endl;
+
+            ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+            "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+            ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+            "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+            ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        }
+
+        for(int i = 0; i<finalStateBlock_vec.size(); i++)
+        {
+            origin_KF->setState(perturbated_origin_state);
+            last_KF->setState(initial_final_state);
+
+            origin_KF->fix();
+            last_KF->fix();
+
+            //we unfix origin VELOCITY stateblock to let it converge
+            originStateBlock_vec[2]->unfix();
+
+            //we now unfix only one StateBlock
+            finalStateBlock_vec[i]->unfix();
+
+            summary = ceres_manager_wolf_diff->solve();
+            //std::cout << summary.BriefReport() << std::endl;
+
+            ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS )) <<
+            "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+            ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        }
+    }
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityOrigin2_Unfix1)
+{
+    /* Here we have only 1 StateBlock unfixed (Plus the velocity StateBlock from origin_KF that we perturbate)
+     * 2 components of origin_KF velocity are perturbated here
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    for(int pert_index0 = 7; pert_index0<10; pert_index0++)
+    {
+        for(int pert_index1 = 8; pert_index1<10; pert_index1++)
+        {
+            //perturbate initial state
+            perturbated_origin_state = initial_origin_state;
+            perturbated_origin_state(pert_index0) += 1.0;
+            perturbated_origin_state(pert_index1) += 1.0;
+
+            for(int i = 1; i<originStateBlock_vec.size(); i++)
+            {
+                origin_KF->setState(perturbated_origin_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->fix();
+                last_KF->fix();
+
+                //we unfix origin VELOCITY stateblock to let it converge
+                originStateBlock_vec[2]->unfix();
+
+                //we now unfix only one StateBlock
+                originStateBlock_vec[i]->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS )) <<
+                "origin orientation : " << last_KF->getOPtr()->getState().transpose() << "\n last orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS )) <<
+                "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+
+            for(int i = 1; i<finalStateBlock_vec.size(); i++)
+            {
+                origin_KF->setState(perturbated_origin_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->fix();
+                last_KF->fix();
+
+                //we unfix origin position stateblock to let it converge
+                originStateBlock_vec[2]->unfix();
+
+                //we now unfix only one StateBlock
+                finalStateBlock_vec[i]->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityOrigin3_Unfix1)
+{
+        /* Here we have only 1 StateBlock unfixed (Plus the velocity StateBlock from origin_KF that we perturbate)
+     * All 3 components of origin_KF velocity are perturbated here.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(7) += 1.0;
+    perturbated_origin_state(8) += 2.0;
+    perturbated_origin_state(9) += 3.0;
+
+    for(int i = 1; i<originStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->fix();
+        last_KF->fix();
+
+        //we unfix origin VELOCITY stateblock to let it converge
+        originStateBlock_vec[2]->unfix();
+
+        //we now unfix only one StateBlock
+        originStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    }
+
+    for(int i = 1; i<finalStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->fix();
+        last_KF->fix();
+
+        //we unfix origin velocity stateblock to let it converge
+        originStateBlock_vec[2]->unfix();
+
+        //we now unfix only one StateBlock
+        finalStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityLast3_Unfix1)
+{
+    /* Here we have only 1 StateBlock unfixed (Plus the velocity StateBlock of last_KF that we perturbate)
+     * All 3 components of last_KF velocity are perturbated here.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    //perturate initial state
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(7) += 1.0;
+    perturbated_final_state(8) += 2.0;
+    perturbated_final_state(9) += 3.0;
+
+    for(int i = 1; i<originStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(initial_origin_state);
+        last_KF->setState(perturbated_final_state);
+
+        origin_KF->fix();
+        last_KF->fix();
+
+        //we unfix origin velocity stateblock to let it converge
+        finalStateBlock_vec[2]->unfix();
+
+        //we now unfix only one StateBlock
+        originStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, 0.0000001 ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 ));
+    }
+
+    for(int i = 1; i<finalStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(initial_origin_state);
+        last_KF->setState(perturbated_final_state);
+
+        origin_KF->fix(); 
+        last_KF->fix();
+
+        //we unfix origin velocity stateblock to let it converge
+        finalStateBlock_vec[2]->unfix();
+
+        //we now unfix only one StateBlock
+        finalStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        EXPECT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+        EXPECT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityOrigin3_UnfixAll)
+{
+    /* Both KeyFrames are unfixed
+     * All 3 components of origin_KF velocity are perturbated here.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(7) += 1.0;
+    perturbated_origin_state(8) += 2.0;
+    perturbated_origin_state(9) += 3.0;
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    /* Here we gave an initial velocity and a final velocity. Everything is unfixed. We did not move between both KF according to
+     * odometry constraint. There is no reason for the origin KF to impose its values to last in an optimization point of view.
+     * the minimal cost should be somewhere between both keyframe velocities. The Robot couldhave done anything between both KF
+     *
+     * Robot could have done anything. Velocity changed. So acc bias could also change to anything... But gyroscope bias should still be 0
+     */
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityLast3_UnfixAll)
+{
+    /* Both KeyFrames are unfixed
+     * All 3 components of last_KF velocity are perturbated here.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(7) += 1.0;
+    perturbated_final_state(8) += 2.0;
+    perturbated_final_state(9) += 3.0;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->unfix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    /* Here we gave an initial velocity and final velocity. Everything is unfixed. We did not move between both KF according to
+     * odometry constraint. But we perturbated the final velocities before optimization.
+     * There is no reason for the origin KF to impose its values to last in an optimization point of view.
+     * the minimal cost should be somewhere between both keyframe velocities.
+     * 
+     * Acceleration bias can also change here. And in fact it will. We may wonder what happens if we only fix acceleration biases (in origin and last KF) :
+     * We can suppose that velocities will be changed even more. The difference in velocity cannot be compensated in acceleration biases but both origin_KF and last_KF
+     * velocities can be changed so that the 'robot' does not move. So we can either expect the velocities to be 0, or we can expect the velocities to be contrary.
+     * But due to IMU constraint saying 'no acceleration' we expect both velocity StateBlocks to be null.
+     * We will try this case in test TEST 9
+     */
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityOrigin3_FixLast)
+{
+    /* last_KF is fixed 
+     * All 3 components of origin_KF velocity are perturbated here.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(7) += 1.0;
+    perturbated_origin_state(8) += 2.0;
+    perturbated_origin_state(9) += 3.0;
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*0.001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityLast3_FixOrigin)
+{
+    /* we only fixed acceleration biases (in origin and last KF) :
+     * We can suppose that velocities will be changed even more. The difference in velocity cannot be compensated in acceleration biases but both origin_KF and last_KF
+     * velocities can be changed so that the 'robot' does not move. So we can either expect the velocities to be 0, or we can expect the velocities to be contrary.
+     * But due to IMU constraint saying 'no acceleration' we expect both velocity StateBlocks to be null.
+    */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(7) += 1.0;
+    perturbated_final_state(8) += 2.0;
+    perturbated_final_state(9) += 3.0;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->fix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*0.001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_velocityLast3_FixAccBiaseS)
+{
+    /* Both KeyFrames are unfixed here. however, all Acceleration bias StateBlocks are fixed.
+     * All 3 components of last_KF velocity are perturbated here.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(7) += 1.0;
+    perturbated_final_state(8) += 2.0;
+    perturbated_final_state(9) += 3.0;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->unfix(); 
+    last_KF->unfix();
+
+    //fix acceleration biases
+    originStateBlock_vec[3]->fix();
+    finalStateBlock_vec[3]->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS*100 )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    // As expected, both velocity StateBlocks converge to 0. The error is in 1e-6
+}   
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation1Origin_Unfix1)
+{
+    /* Both KeyFrames are fixed. We unfix 1 stateblock among those we have in these 2 KeyFrames.
+     * We perturbate 1 orientation (ox, oy, oz) in origin_KF. ==> We also unfix origin_KF's quaternion StateBlock.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    for(int pert_index = 0; pert_index<3; pert_index++)
+    {
+        Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+        perturbated_origin_state = initial_origin_state;
+        Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+        orientation_perturbation(pert_index) += 1.0;
+
+        //introduce the perturbation directly in the quaternion StateBlock
+        quat_map = quat_map * v2q(orientation_perturbation);
+
+        for(int i = 0; i<originStateBlock_vec.size(); i++)
+        {
+            origin_KF->setState(perturbated_origin_state);
+            last_KF->setState(initial_final_state);
+
+            origin_KF->fix();
+            last_KF->fix();
+
+            //we unfix origin orientation stateblock to let it converge
+            originStateBlock_vec[1]->unfix();
+            
+            //we now unfix one StateBlock
+            originStateBlock_vec[i]->unfix();
+
+            summary = ceres_manager_wolf_diff->solve();
+            //std::cout << summary.BriefReport() << std::endl;
+
+            ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+            "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+            ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+            ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+            ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        }
+
+        for(int i = 0; i<finalStateBlock_vec.size(); i++)
+        {
+            origin_KF->setState(perturbated_origin_state);
+            last_KF->setState(initial_final_state);
+
+            origin_KF->fix();
+            last_KF->fix();
+
+            //we unfix origin orientation stateblock to let it converge
+            originStateBlock_vec[1]->unfix();
+
+            //we now unfix only one StateBlock
+            finalStateBlock_vec[i]->unfix();
+
+            summary = ceres_manager_wolf_diff->solve();
+            //std::cout << summary.BriefReport() << std::endl;
+
+            ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+            "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+            ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+            ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+            ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+            ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+            "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+            // ifgyro bias stateBlock is the only one unfixed. it will be changed so that conditions can be met on orientation.
+            ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 ));
+        }
+    }
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation2Origin_Unfix1)
+{
+    /* Both KeyFrames are fixed. We unfix 1 stateblock among those we have in these 2 KeyFrames.
+     * We perturbate 2 angles (ox, oy, oz) in origin_KF. ==> We also unfix origin_KF's quaternion StateBlock.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    for(int pert_index0 = 0; pert_index0<3; pert_index0++)
+    {
+        for(int pert_index1 = 1; pert_index1<3; pert_index1++)
+        {
+            //perturate initial state
+            Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+            perturbated_origin_state = initial_origin_state;
+
+            Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+            orientation_perturbation(pert_index0) += 1.0;
+            orientation_perturbation(pert_index1) += 1.0;
+
+            //introduce the perturbation directly in the quaternion StateBlock
+            quat_map = quat_map * v2q(orientation_perturbation);
+
+            for(int i = 0; i<originStateBlock_vec.size(); i++)
+            {
+                origin_KF->setState(perturbated_origin_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->fix();
+                last_KF->fix();
+
+                //we unfix origin ORIENTATION stateblock to let it converge
+                originStateBlock_vec[1]->unfix();
+                
+                //we now unfix only one StateBlock
+                originStateBlock_vec[i]->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+                "origin orientation : " << last_KF->getOPtr()->getState().transpose() << "\n last orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+                "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+            }
+
+            for(int i = 0; i<finalStateBlock_vec.size(); i++)
+            {
+                origin_KF->setState(perturbated_origin_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->fix();
+                last_KF->fix();
+
+                //we unfix origin ORIENTATION stateblock to let it converge
+                originStateBlock_vec[1]->unfix();
+
+                //we now unfix only one StateBlock
+                finalStateBlock_vec[i]->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+                
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                if(i != 1) //if we do not fix origin_KF Quaternion StateBlock we cannot expect to have unit Quaternion here
+                    ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+                    "last orientation state : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Origin_Unfix1)
+{
+    /* Both KeyFrames are fixed. We unfix 1 stateblock among those we have in these 2 KeyFrames.
+     * We perturbate all 3 angles (ox, oy, oz) in origin_KF. ==> We also unfix origin_KF's quaternion StateBlock.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_origin_state = initial_origin_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 0.5; 
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    quat_map = quat_map * v2q(orientation_perturbation);
+
+    for(int i = 0; i<originStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->fix();
+        last_KF->fix();
+        
+        //we unfix origin ORIENTATION stateblock to let it converge
+        originStateBlock_vec[1]->unfix();
+
+        //we now unfix only one StateBlock
+        originStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+        "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+        "last orientation state : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 ));
+    }
+
+    for(int i = 0; i<finalStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->fix(); 
+        last_KF->fix();
+
+        //we unfix origin ORIENTATION stateblock to let it converge
+        originStateBlock_vec[1]->unfix();
+
+        //we now unfix only one StateBlock
+        finalStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )); //because we simulate a perfect IMU
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )); //because we simulate a perfect IMU
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+        if(i != 1) //if orientation block is the only one unfixed it will be changed
+            ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, 0.0000001 ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 ));
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Last_Unfix1)
+{
+    /* Both KeyFrames are fixed. We unfix 1 stateblock among those we have in these 2 KeyFrames.
+     * We perturbate all 3 angles (ox, oy, oz) in last_KF. ==> We also unfix last_KF's quaternion StateBlock.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+    
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_final_state = initial_final_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_final_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 1.0;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    quat_map = quat_map * v2q(orientation_perturbation);
+
+    for(int i = 1; i<originStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(initial_origin_state);
+        last_KF->setState(perturbated_final_state);
+
+        origin_KF->fix(); //this fix the all keyframe
+        last_KF->fix();
+
+        //we unfix final orientation stateblock to let it converge
+        finalStateBlock_vec[1]->unfix();
+
+        //we now unfix only one StateBlock
+        originStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+        // if only orientation stateblocks are unfixed. We can hardly expect the final orienation to converge toward the one in origin_KF.
+        // Both are likely to be changed to an intermediate orientation state.
+        // but in the other cases, if origin orientation is fixed to identity quaternion and the robot did not move we expect the final orientation to converge to identity quaternion too
+        if(i != 1) 
+            ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, 0.0000001 )) << "last orientation state : " << last_KF->getOPtr()->getState().transpose() ;
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, 0.0000001 ));
+    }
+
+    for(int i = 1; i<finalStateBlock_vec.size(); i++)
+    {
+        origin_KF->setState(initial_origin_state);
+        last_KF->setState(perturbated_final_state);
+
+        origin_KF->fix();
+        last_KF->fix();
+
+        //we unfix final orientation stateblock to let it converge
+        finalStateBlock_vec[1]->unfix();
+
+        //we now unfix only one StateBlock
+        finalStateBlock_vec[i]->unfix();
+
+        summary = ceres_manager_wolf_diff->solve();
+        //std::cout << summary.BriefReport() << std::endl;
+
+        EXPECT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+        EXPECT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Origin_UnfixAll)
+{
+    /* Both KeyFrames are unfixed.
+     * We perturbate all 3 angles (ox, oy, oz) in origin_KF.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_origin_state = initial_origin_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 3.0; //DOES NOT WORK IF = 3.0
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    //quat_map = quat_map * v2q(orientation_perturbation);
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last KF orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin KF orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    /* Here we gave an initial orientation and a final orientation. Everything is unfixed. We did not move between both KF according to
+     * odometry constraint. There is no reason for the origin KF to impose its values to last in an optimization point of view.
+     * the minimal cost should be somewhere between both keyframe velocities. The Robot couldhave done anything between both KF.
+     * However, IMU constraint imposes no rate of turn. So we expect both velocities to be equal after optimization but biases could have been changed. Or bias is
+     * unchanged and orientations have changed or both have been changed.
+     */
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Last_UnfixAll)
+{
+    /* Both KeyFrames are unfixed.
+     * We perturbate all 3 angles (ox, oy, oz) in last_KF.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_final_state = initial_final_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_final_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 1.0;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    //quat_map = quat_map * v2q(orientation_perturbation);
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->unfix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    /* Here we gave an initial orientation and final orientation. Everything is unfixed. We did not move between both KF according to
+     * odometry constraint. But we perturbated the final orientation before optimization.
+     * There is no reason for the origin KF to impose its values to last in an optimization point of view.
+     * the minimal cost should be somewhere between both keyframe orientations.
+     */
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3origin_FixLast)
+{
+    /* Both KeyFrames are unfixed.
+     * We perturbate all 3 angles (ox, oy, oz) in origin_KF.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_origin_state = initial_origin_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 1.0;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    //quat_map = quat_map * v2q(orientation_perturbation);
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*0.001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    EXPECT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last KF orientation : " << last_KF->getOPtr()->getState().transpose() << "\norigin KF orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    EXPECT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Last_FixOrigin)
+{
+    /* we only fixed gyroscope biases (in origin and last KF) :
+     * We can suppose that orientation will be changed even more. The difference in orientation cannot be compensated in gyroscope biases but both origin_KF and last_KF
+     * orientations can be changed so that the 'robot' does not move. So we can either expect the orientation to be 0.
+     * Due to IMU constraint saying 'no rate of turn' we expect both velocity StateBlocks to be null.
+    */
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_final_state = initial_final_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_final_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 1.0;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    //quat_map = quat_map * v2q(orientation_perturbation);
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->fix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*0.001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Last_FixGyroBiaseS)
+{
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_final_state = initial_final_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_final_state.data() + 3);
+
+    orientation_perturbation(0) = 1.0;
+    orientation_perturbation(1) = 2.0;
+    orientation_perturbation(2) = 1.0;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    //quat_map = quat_map * v2q(orientation_perturbation);
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->unfix();
+    last_KF->unfix();
+    
+    //fix gyroscope biases
+    originStateBlock_vec[4]->fix();
+    finalStateBlock_vec[4]->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS));
+    EXPECT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS*100 )) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    // As expected, both velocity StateBlocks converge to 0. The error is in 1e-6
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_AccBiasOrigin_FixedLast)
+{
+    /* last_KF is fixed. Origin_KF is unfixed
+     * Accelerometer bias of origin_KF is perturbated. 
+     * We expect Ceres to be able to converge anyway and solve the problem so that the bias goes back to Zero
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(10) += 1.0;
+    perturbated_origin_state(11) += 2.0;
+    perturbated_origin_state(12) += 4.0;
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_AccBiasLast_FixedOrigin)
+{
+    /* Origin_KF is fixed. Last_KF is unfixed
+     * Accelerometer bias of Last_KF is perturbated. 
+     * Let's think about the situation we have here ... The problem is that the sensor bias in t2 has no effect on all measurements made before t2 
+     * and thus no efect on keyFrames created before timeStamp t2 (except if the bias was always the same...)
+     * Thus we do not expect the acc bias to be changed by CERES.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin.
+     */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(10) += 1.0;
+    perturbated_final_state(11) += 2.0;
+    perturbated_final_state(12) += 3.0;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->fix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    //See description above to understand why we assert this to be false
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_GyroBiasOrigin_FixedLast)
+{
+    /* last_KF is fixed. Origin_KF is unfixed
+     * Gyrometer bias of origin_KF is perturbated. 
+     * We expect Ceres to be able to converge anyway and solve the problem so that the bias goes back to Zero
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(13) += 1.0;
+    perturbated_origin_state(14) += 0.5;
+    perturbated_origin_state(15) += 1.5;
+
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->unfix();
+    last_KF->fix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last gyro bias : " << last_KF->getGyroBiasPtr()->getState().transpose() << "\n origin gyro bias : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_GyroBiaslast_FixedOrigin)
+{
+    /* Origin_KF is fixed. Last_KF is unfixed
+     * Gyrometer bias of Last_KF is perturbated. 
+     *
+     * Let's think about the situation we have here ... The problem is that the sensor bias in t2 has no effect on all measurements made before t2 
+     * and thus no efect on keyFrames created before timeStamp t2 (except if the bias was always the same...)
+     * Thus we do not expect the gyroscope bias to be changed by CERES.
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    perturbated_final_state = initial_final_state;
+    perturbated_final_state(13) += 1.0;
+    perturbated_final_state(14) += 1.5;
+    perturbated_final_state(15) += 0.8;
+
+    origin_KF->setState(initial_origin_state);
+    last_KF->setState(perturbated_final_state);
+
+    origin_KF->fix();
+    last_KF->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+    "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    //See description to understand why we assert this to false
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last gyro bias : " << last_KF->getGyroBiasPtr()->getState().transpose() << "\n origin gyro bias : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests, static_Optim_IMUOdom_2KF)
+{
+
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving and we add an odometry measurement.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same
+     * Origin KeyFrame is fixed
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1
+     *     \____constraintOdom3D___/
+     *
+     *
+     * With IMU data only, biases are not observable ! So covariance cannot be computed due to jacobian rank deficiency.
+     * We must add an odometry to make covariances computable
+     */
+
+     //===================================================== END OF SETTINGS
+
+     // set origin of processorMotions
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+    t.set(0);
+
+    FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+    //There should be 3 captures at origin_frame : CaptureOdom, captureIMU
+    EXPECT_EQ((wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front())->getCaptureList().size(),2);
+    ASSERT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isKey()) << "origin_frame is not a KeyFrame..." << std::endl;
+
+    //===================================================== END{END OF SETTINGS}
+
+    //===================================================== PROCESS DATA
+
+    // PROCESS IMU DATA
+
+    Eigen::Vector6s data;
+    data << 0.00, 0.000, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+    Scalar dt = t.get();
+    TimeStamp ts(0.001);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+    while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()) ){
+        
+        // Time and data variables
+        dt += 0.001;
+        ts.set(dt);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    // PROCESS ODOM 3D DATA
+    Eigen::Vector6s data_odom3D;
+    data_odom3D << 0,0,0, 0,0,0;
+    
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+    sen_odom3D->process(mot_ptr);
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+
+}
+
+/* 2 of the tests above seem to indicate that more precise tests are required :
+ *  - ProcessorIMU_Odom_tests_details.static_Optim_IMUOdom_2KF_perturbate_GyroBiasOrigin_FixedLast :
+ *          If the gyroscope perturbation is too strong, then the test does not pass, from tests below , we see that when we introduce perturbation along 1 axis only
+ *          then this threshold is the same on all axis : PI
+ *          If another gyr+oscope bias is perturbated, then the threshold is different
+ */
+
+ TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_GyroBiasOrigin_FixedLast_ext_bwx)
+{
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(13) += M_PI-0.002;
+
+    //loop over the bwz to find the problematic threshold
+    for(int i = 0; i<2 ; i++)
+    {
+        perturbated_origin_state(13) += 0.001;
+
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->unfix();
+        last_KF->fix();
+
+        summary = ceres_manager_wolf_diff->solve();
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+        
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+            
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+            
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last gyro bias : " << last_KF->getGyroBiasPtr()->getState().transpose() << "\n origin gyro bias : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+    }  
+}
+
+ TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_GyroBiasOrigin_FixedLast_ext_bwy)
+{
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(14) += M_PI-0.002;
+
+    //loop over the bwz to find the problematic threshold
+    for(int i = 0; i<4 ; i++)
+    {
+        perturbated_origin_state(14) += 0.001;
+
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->unfix();
+        last_KF->fix();
+
+        summary = ceres_manager_wolf_diff->solve();
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+            
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+            
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last gyro bias : " << last_KF->getGyroBiasPtr()->getState().transpose() << "\n origin gyro bias : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+    }
+}
+
+ TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_GyroBiasOrigin_FixedLast_ext_bwz)
+{
+    /* last_KF is fixed. Origin_KF is unfixed
+     * Gyrometer bias of origin_KF is perturbated. 
+     * We expect Ceres to be able to converge anyway and solve the problem so that the bias goes back to Zero
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     *
+     * Due to detected strange behaviour. We try here to see how perturbated can a gyroscope bias value be before the optimation gives incorrect values
+     *
+     * Z axis is special since it will measure gravity in this static context
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(15) += M_PI-0.002;
+
+    //loop over the bwz to find the problematic threshold
+    for(int i = 0; i<3 ; i++)
+    {
+        perturbated_origin_state(15) += 0.001;
+
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->unfix();
+        last_KF->fix();
+
+        summary = ceres_manager_wolf_diff->solve();
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+        
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+            
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last gyro bias : " << last_KF->getGyroBiasPtr()->getState().transpose() << "\n origin gyro bias : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+    }
+}
+
+ TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_GyroBiasOrigin_FixedLast_ext_bwxy)
+{
+    /* last_KF is fixed. Origin_KF is unfixed
+     * Gyrometer bias of origin_KF is perturbated. 
+     * We expect Ceres to be able to converge anyway and solve the problem so that the bias goes back to Zero
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     *
+     *Due to detected strange behaviour. We try here to see how perturbated can a gyroscope bias value be before the optimation gives incorrect values
+     */
+
+    perturbated_origin_state = initial_origin_state;
+    perturbated_origin_state(13) += M_PI - 1;
+    perturbated_origin_state(14) += 2.1;
+
+    //loop over the bwz to find the problematic threshold
+    for(int i = 0; i<3 ; i++)
+    {
+        perturbated_origin_state(14) += 0.1;
+
+        origin_KF->setState(perturbated_origin_state);
+        last_KF->setState(initial_final_state);
+
+        origin_KF->unfix();
+        last_KF->fix();
+
+        summary = ceres_manager_wolf_diff->solve();
+
+        ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+        ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS)) <<
+        "last velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << "\n origin acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+        ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+        "last gyro bias : " << last_KF->getGyroBiasPtr()->getState().transpose() << "\n origin gyro bias : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+    }
+}
+
+/*  - ProcessorIMU_Odom_tests_details.static_Optim_IMUOdom_2KF_perturbate_orientation3Origin_Unfix1 :
+ *          If the introduced orientation perturbation is bigger than pi then the test does not pass.
+ */
+
+TEST_F(ProcessorIMU_Odom_tests_details, static_Optim_IMUOdom_2KF_perturbate_orientation3Origin_Unfix1_ext)
+{
+    /* Both KeyFrames are fixed. We unfix 1 stateblock among those we have in these 2 KeyFrames.
+     * We perturbate all 3 angles (ox, oy, oz) in origin_KF. ==> We also unfix origin_KF's quaternion StateBlock.
+     * The perturbation is introduced in this quaternion stateblocks using q * v2q(rotation_vector_perturbation)
+     *
+     * Odom and IMU contraints say that the 'robot' did not move between both KeyFrames.
+     * So we expect CERES to converge so that origin_KF (=) last_KF meaning that all the stateBlocks should ideally be equal and at the origin..
+     */
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    perturbated_origin_state = initial_origin_state;
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+
+    //M_PI not passed, it should work
+    perturbated_origin_state = initial_origin_state;
+    orientation_perturbation(2) += M_PI;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    quat_map = quat_map * v2q(orientation_perturbation);
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->fix();
+    last_KF->fix();
+        
+    //we unfix origin ORIENTATION stateblock to let it converge
+    originStateBlock_vec[1]->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+    "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+
+    // Now we reach PI, and it will not work 
+    orientation_perturbation(2) = M_PI+0.0001;
+
+    perturbated_origin_state = initial_origin_state;
+
+    //introduce the perturbation directly in the quaternion StateBlock
+    quat_map = quat_map * v2q(orientation_perturbation);
+    origin_KF->setState(perturbated_origin_state);
+    last_KF->setState(initial_final_state);
+
+    origin_KF->fix();
+    last_KF->fix();
+        
+    //we unfix origin ORIENTATION stateblock to let it converge
+    originStateBlock_vec[1]->unfix();
+
+    summary = ceres_manager_wolf_diff->solve();
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, 0.00000001 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+    EXPECT_FALSE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+    "last orientation : " << last_KF->getOPtr()->getState().transpose() << "\n origin orientation : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  0.00000001 ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00000001 ));
+}
+
+//_______________________________________________________________________________________________________________
+// END ##################################### static_Optim_IMUOdom_2KF TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+
+//_______________________________________________________________________________________________________________
+// ##################################### static_Optim_IMUOdom_3KF TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+/*  Tests below will be based on the following representation :
+ *     KF0 ---- constraintIMU ---- KF1 --- constraintIMU -- KF2
+ *        \____constraintOdom3D___/  \____constraintOdom3D___/
+ */
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbatePositionOrigin_fixLast)
+{
+    /* We perturbate the origin KF and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want tomake sure that the middle KF will not have undesired behaviour.
+     *
+     * We notice some strange thing about acceleration bias here.
+     * We could think that the optimizer can use the fact that origin and middle KF are unfixed and use acc biases to satisfy position conditions given odom and imu constraints
+     * Thus we cannot expect accelerometer bias in origin_KF and middle_KF to be equal 
+     * in practice, We notice that if we perturbate Pz in origin_KF, then the equality of acc biases in origin and middle_KF is met.
+     * but if Pz is not perturbated then this equality does not seem to be true. 
+     * We can wonder what will happen if acc bias stateBlocks are fixed. We investigate this in the next test
+     */
+
+
+    for(int pert_index0 = 0; pert_index0<3; pert_index0++)
+    {
+        for(int pert_index1 = 0; pert_index1<3; pert_index1++)
+        {
+            for(int pert_index2 = 0; pert_index2<3; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_origin_state = initial_origin_state;
+                perturbated_origin_state(pert_index0) += 1.0;
+                perturbated_origin_state(pert_index1) += 1.0;
+                perturbated_origin_state(pert_index2) += 1.0;
+
+                origin_KF->setState(perturbated_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->unfix();
+                middle_KF->unfix();
+                last_KF->fix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+
+                /*EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() <<
+                "\n perturbation index : " << pert_index0 << "." << pert_index1 << "." << pert_index2 << std::endl;*/
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbatePositionOrigin_fixLast_fixAccBiaseS)
+{
+    /* We perturbate the origin KF and fix the last KF. (origin_KF and middle_KF are unfixed) All Accelerometer biase StateBlocks are fixed
+     * We want tomake sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 0; pert_index0<3; pert_index0++)
+    {
+        for(int pert_index1 = 0; pert_index1<3; pert_index1++)
+        {
+            for(int pert_index2 = 0; pert_index2<3; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_origin_state = initial_origin_state;
+                perturbated_origin_state(pert_index0) += 1.0;
+                perturbated_origin_state(pert_index1) += 1.0;
+                perturbated_origin_state(pert_index2) += 1.0;
+
+                origin_KF->setState(perturbated_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->unfix();
+                middle_KF->unfix();
+                originStateBlock_vec[3]->fix();
+                middleStateBlock_vec[3]->fix();
+                last_KF->fix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() <<
+                "\n perturbation index : " << pert_index0 << "." << pert_index1 << "." << pert_index2 << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateVelocityOrigin_fixLast)
+{
+    /* We perturbate the origin KF (velocity) and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want tomake sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 7; pert_index0<10; pert_index0++)
+    {
+        for(int pert_index1 = 7; pert_index1<10; pert_index1++)
+        {
+            for(int pert_index2 = 7; pert_index2<10; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_origin_state = initial_origin_state;
+                perturbated_origin_state(pert_index0) += 1.0;
+                perturbated_origin_state(pert_index1) += 1.0;
+                perturbated_origin_state(pert_index2) += 1.0;
+
+                origin_KF->setState(perturbated_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->unfix();
+                middle_KF->unfix();
+                last_KF->fix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() <<
+                "\n perturbation index : " << pert_index0 << "." << pert_index1 << "." << pert_index2 << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateOrientationOrigin_fixLast)
+{
+    /* We perturbate the origin KF (orientation) and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want tomake sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 0; pert_index0<3; pert_index0++)
+    {
+        for(int pert_index1 = 0; pert_index1<3; pert_index1++)
+        {
+            for(int pert_index2 = 0; pert_index2<3; pert_index2++)
+            {
+                //perturate initial state
+                Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+                orientation_perturbation(pert_index0) += 0.5;
+                orientation_perturbation(pert_index1) += 0.5;
+                orientation_perturbation(pert_index2) += 0.5;
+
+                perturbated_origin_state = initial_origin_state;
+                Eigen::Map<Eigen::Quaternions> quat_map(perturbated_origin_state.data() + 3);
+
+                //introduce the perturbation directly in the quaternion StateBlock
+                quat_map = quat_map * v2q(orientation_perturbation);
+
+                origin_KF->setState(perturbated_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->unfix();
+                middle_KF->unfix();
+                last_KF->fix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() <<
+                "\n perturbation index : " << pert_index0 << "." << pert_index1 << "." << pert_index2 << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateAccBiasOrigin_fixLast)
+{
+    /* We perturbate the origin KF (Acc bias) and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want to make sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 10; pert_index0<13; pert_index0++)
+    {
+        for(int pert_index1 = 10; pert_index1<13; pert_index1++)
+        {
+            for(int pert_index2 = 10; pert_index2<13; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_origin_state = initial_origin_state;
+                perturbated_origin_state(pert_index0) += 1.0;
+                perturbated_origin_state(pert_index1) += 1.0;
+                perturbated_origin_state(pert_index2) += 1.0;
+
+                origin_KF->setState(perturbated_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->unfix();
+                middle_KF->unfix();
+                last_KF->fix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateGyroBiasOrigin_fixLast)
+{
+    /* We perturbate the origin KF (Acc bias) and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want to make sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 13; pert_index0<16; pert_index0++)
+    {
+        for(int pert_index1 = 13; pert_index1<16; pert_index1++)
+        {
+            for(int pert_index2 = 13; pert_index2<16; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_origin_state = initial_origin_state;
+                perturbated_origin_state(pert_index0) += 0.5;
+                perturbated_origin_state(pert_index1) += 0.5;
+                perturbated_origin_state(pert_index2) += 0.5;
+
+                origin_KF->setState(perturbated_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(initial_final_state);
+
+                origin_KF->unfix();
+                middle_KF->unfix();
+                last_KF->fix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbatePositionLast_fixOrigin)
+{
+    /* We perturbate the origin KF and fix the last KF. (last_KF and middle_KF are unfixed)
+     * We want to make sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 0; pert_index0<3; pert_index0++)
+    {
+        for(int pert_index1 = 0; pert_index1<3; pert_index1++)
+        {
+            for(int pert_index2 = 0; pert_index2<3; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_final_state = initial_final_state;
+                perturbated_final_state(pert_index0) += 1.0;
+                perturbated_final_state(pert_index1) += 1.0;
+                perturbated_final_state(pert_index2) += 1.0;
+
+                origin_KF->setState(initial_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(perturbated_final_state);
+
+                origin_KF->fix();
+                middle_KF->unfix();
+                last_KF->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() <<
+                "\n perturbation index : " << pert_index0 << "." << pert_index1 << "." << pert_index2 << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateVelocityLast_fixOrigin)
+{
+    /* We perturbate the last KF (velocity) and fix the origin KF. (last_KF and middle_KF are unfixed)
+     * We want tomake sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 7; pert_index0<10; pert_index0++)
+    {
+        for(int pert_index1 = 7; pert_index1<10; pert_index1++)
+        {
+            for(int pert_index2 = 7; pert_index2<10; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_final_state = initial_final_state;
+                perturbated_final_state(pert_index0) += 1.0;
+                perturbated_final_state(pert_index1) += 1.0;
+                perturbated_final_state(pert_index2) += 1.0;
+
+                origin_KF->setState(initial_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(perturbated_final_state);
+
+                origin_KF->fix();
+                middle_KF->unfix();
+                last_KF->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() <<
+                "\n perturbation index : " << pert_index0 << "." << pert_index1 << "." << pert_index2 << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateOrientationLast_fixOrigin)
+{
+    /* We perturbate the last KF (orientation) and fix the last KF. (last_KF and middle_KF are unfixed)
+     * We want to make sure that the middle KF will not have undesired behaviour.
+     */
+
+    for(int pert_index0 = 0; pert_index0<3; pert_index0++)
+    {
+        for(int pert_index1 = 0; pert_index1<3; pert_index1++)
+        {
+            for(int pert_index2 = 0; pert_index2<3; pert_index2++)
+            {
+                //perturate initial state
+                Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+                orientation_perturbation(pert_index0) += 0.5;
+                orientation_perturbation(pert_index1) += 0.5;
+                orientation_perturbation(pert_index2) += 0.5;
+
+                perturbated_final_state = initial_final_state;
+                Eigen::Map<Eigen::Quaternions> quat_map(perturbated_final_state.data() + 3);
+
+                //introduce the perturbation directly in the quaternion StateBlock
+                quat_map = quat_map * v2q(orientation_perturbation);
+
+                origin_KF->setState(initial_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(perturbated_final_state);
+
+                origin_KF->fix();
+                middle_KF->unfix();
+                last_KF->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateAccBiasLast_fixOrigin)
+{
+    /* We perturbate the origin KF (Acc bias) and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want to make sure that the middle KF will not have undesired behaviour.
+     *
+     * Bias at timeStamp t does not have influence on keyFrames from timeStamp before t.
+     * Hence we cannot expect the perturbated acc bias in last KF to converge toward the acc bias of origin_KF
+     */
+
+    for(int pert_index0 = 10; pert_index0<13; pert_index0++)
+    {
+        for(int pert_index1 = 10; pert_index1<13; pert_index1++)
+        {
+            for(int pert_index2 = 10; pert_index2<13; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_final_state = initial_final_state;
+                perturbated_final_state(pert_index0) += 1.0;
+                perturbated_final_state(pert_index1) += 1.0;
+                perturbated_final_state(pert_index2) += 1.0;
+
+                origin_KF->setState(initial_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(perturbated_final_state);
+
+                origin_KF->fix();
+                middle_KF->unfix();
+                last_KF->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+
+                //See description above to understand why we expect this test in ac bias to be false.
+                EXPECT_FALSE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                EXPECT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_details3KF, static_optim_IMUOdom_perturbateGyroBiasLast_fixOrigin)
+{
+    /* We perturbate the origin KF (Acc bias) and fix the last KF. (origin_KF and middle_KF are unfixed)
+     * We want to make sure that the middle KF will not have undesired behaviour.
+     *
+     * Bias at timeStamp t does not have influence on keyFrames from timeStamp before t.
+     * Hence we cannot expect the perturbated gyro bias in last KF to converge toward the gyro bias of origin_KF
+     */
+
+    for(int pert_index0 = 13; pert_index0<16; pert_index0++)
+    {
+        for(int pert_index1 = 13; pert_index1<16; pert_index1++)
+        {
+            for(int pert_index2 = 13; pert_index2<16; pert_index2++)
+            {
+                //perturate initial state
+                perturbated_final_state = initial_final_state;
+                perturbated_final_state(pert_index0) += 0.5;
+                perturbated_final_state(pert_index1) += 0.5;
+                perturbated_final_state(pert_index2) += 0.5;
+
+                origin_KF->setState(initial_origin_state);
+                middle_KF->setState(initial_middle_state);
+                last_KF->setState(perturbated_final_state);
+
+                origin_KF->fix();
+                middle_KF->unfix();
+                last_KF->unfix();
+
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //test last against origin
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                // See description to understand why this we expect the gyroscope bias test below to be false
+                EXPECT_FALSE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+                //test middle against origin
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS_SMALL*1000 ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle_KF acc bias : " << middle_KF->getAccBiasPtr()->getState().transpose() << "\n origin_KF acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getPPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "middle position state : " << middle_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (middle_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+                ASSERT_TRUE( (middle_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+            }
+        }
+    }
+}
+
+//_______________________________________________________________________________________________________________
+// END ##################################### static_Optim_IMUOdom_3KF TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+//_______________________________________________________________________________________________________________
+// ##################################### Plateform TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+/* Tests above were designed to make sure everything workds well with a static IMU. This means that the imu should record no move, the odometry says we
+ * did not move and did not turn. As a consequence anything measured by IMU is likely to affect biases or initial conditions of the problem.
+ * 
+ * In the following test we  use a 3D printed IMU plateform to check the results of the optimization. This plateform imposes a final odometry linking
+ * origin_KF and last_KF with a motion of [Px=0    Py=0.06    Pz=0   Ox=0   Oy=0   Oz=0] or a null motion (our choice)
+ *
+ * Final graph is :
+ *      KF0 ---- constraintIMU ---- KF1
+ *        \____constraintOdom3D____/
+ *
+ * Needed : The test will use 1 data files which shall meet the following requirements :
+ *
+ * - a file containing only imu data in IMU frame will be provided. IMU data shall be written in the form [ax, ay, az, wx, wy, wz].
+ *      The IMU measurements must include the measurement of the gravity.
+ *      First line of this file will contain the initial condition in position, orientation and velocity only. (PQV formulation)
+ *      Each line of the file correspond to a new set of IMU data.
+ *      Each data will be separated from the previous one with a tabulation (\t).
+ *      Finally, the following should give a clear idea of how the file is and summarizes the previous points :
+ *          (line1) px_initial\t   py_initial\t   pz_initial\t   qx_initial\t   qy_initial\t   qz_initial\t   qw_initial\t   vx_initial\t   vy_initial\t   vz_initial\t 
+ *          (line2) TimesTamp1\t   ax1\t   ay1\t   az1\t   wx1\t   wy1\t   wz1\t   
+ *          (line3) TimesTamp2\t   ax2\t   ay2\t   az2\t   wx2\t   wy2\t   wz2\t   
+ *          (.           .           .       .       .       .       .       .  )
+ *          (lineN) TimesTampN\t   axN\t   ayN\t   azN\t   wxN\t   wyN\t   wzN\t
+ *
+ * We first integrate all the IMU data provided by the file.
+ * Filepaths are hardcoded in the code and must be placed in src folder. Once all IMU data have been integrated we use the last timestamp to feed
+ * ProcessorOdom3D with a last data (that will link origin_KF to last_KF)
+ */
+
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move)
+{
+    /* last_KF is unfixed. PQV of origin_state are fixed but Acc and Gyro bias StateBlocks are unfixed.*/
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //prepare creation of file if DEBUG_RESULTS activated
+    #ifdef DEBUG_RESULTS
+        std::ofstream debug_results;
+        debug_results.open("debug_results.dat");
+        if(debug_results)
+            debug_results << "%%TimeStamp\t"
+                        << "dp_x\t" << "dp_y\t" << "dp_z\t" << "dq_x\t" << "dq_y\t" << "dq_z\t" << "dq_w\t" << "dv_x\t" << "dv_y\t" << "dv_z\t"
+                        << "Dp_x\t" << "Dp_y\t" << "Dp_z\t" << "Dq_x\t" << "Dq_y\t" << "Dq_z\t" << "Dq_w\t" << "Dv_x\t" << "Dv_y\t" << "Dv_z\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t" << std::endl;
+    #endif
+
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+
+    origin_imuKF->getPPtr()->fix();
+    origin_imuKF->getOPtr()->fix();
+    origin_imuKF->getVPtr()->fix();
+    origin_imuKF->getAccBiasPtr()->unfix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    //closing file
+    imu_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+    //wolf_problem_ptr_->print(4,1,1,1);
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    //test last against origin
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    //ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    //EXPECT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_5s_move)
+{
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_5s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //prepare creation of file if DEBUG_RESULTS activated
+    #ifdef DEBUG_RESULTS
+        std::ofstream debug_results;
+        debug_results.open("debug_results.dat");
+        if(debug_results)
+            debug_results << "%%TimeStamp\t"
+                        << "dp_x\t" << "dp_y\t" << "dp_z\t" << "dq_x\t" << "dq_y\t" << "dq_z\t" << "dq_w\t" << "dv_x\t" << "dv_y\t" << "dv_z\t"
+                        << "Dp_x\t" << "Dp_y\t" << "Dp_z\t" << "Dq_x\t" << "Dq_y\t" << "Dq_z\t" << "Dq_w\t" << "Dv_x\t" << "Dv_y\t" << "Dv_z\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t" << std::endl;
+    #endif
+
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+
+    origin_imuKF->getPPtr()->fix();
+    origin_imuKF->getOPtr()->fix();
+    origin_imuKF->getVPtr()->fix();
+    origin_imuKF->getAccBiasPtr()->unfix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+    
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    //test last against origin
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    //ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1,  wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    //EXPECT_TRUE( (last_KF->getVPtr()->getState() - (Eigen::Vector3s()<<0,0,0).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+//Fix final position
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_fixLastPosition)
+{
+    /* 
+     * Fixing last position has no noticeable consequence in this case compared to the non-fixed case.
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //prepare creation of file if DEBUG_RESULTS activated
+    #ifdef DEBUG_RESULTS
+        std::ofstream debug_results;
+        debug_results.open("debug_results.dat");
+        if(debug_results)
+            debug_results << "%%TimeStamp\t"
+                        << "dp_x\t" << "dp_y\t" << "dp_z\t" << "dq_x\t" << "dq_y\t" << "dq_z\t" << "dq_w\t" << "dv_x\t" << "dv_y\t" << "dv_z\t"
+                        << "Dp_x\t" << "Dp_y\t" << "Dp_z\t" << "Dq_x\t" << "Dq_y\t" << "Dq_z\t" << "Dq_w\t" << "Dv_x\t" << "Dv_y\t" << "Dv_z\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t" << std::endl;
+    #endif
+
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+
+    origin_imuKF->getPPtr()->fix();
+    origin_imuKF->getOPtr()->fix();
+    origin_imuKF->getVPtr()->fix();
+    origin_imuKF->getAccBiasPtr()->unfix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    last_KF->getPPtr()->fix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ));
+    
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+//Fix final position and velocity and orientation
+// -> optimization affects origin_KF's biases
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_fixLastPQV)
+{
+    /* Trajectory
+     * This test passes. Bias estimates are not incoherent.
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //prepare creation of file if DEBUG_RESULTS activated
+    #ifdef DEBUG_RESULTS
+        std::ofstream debug_results;
+        debug_results.open("debug_results.dat");
+        if(debug_results)
+            debug_results << "%%TimeStamp\t"
+                        << "dp_x\t" << "dp_y\t" << "dp_z\t" << "dq_x\t" << "dq_y\t" << "dq_z\t" << "dq_w\t" << "dv_x\t" << "dv_y\t" << "dv_z\t"
+                        << "Dp_x\t" << "Dp_y\t" << "Dp_z\t" << "Dq_x\t" << "Dq_y\t" << "Dq_z\t" << "Dq_w\t" << "Dv_x\t" << "Dv_y\t" << "Dv_z\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t" << std::endl;
+    #endif
+
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+
+    origin_imuKF->getPPtr()->fix();
+    origin_imuKF->getOPtr()->fix();
+    origin_imuKF->getVPtr()->fix();
+    origin_imuKF->getAccBiasPtr()->unfix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    last_KF->getPPtr()->fix();
+    last_KF->getVPtr()->fix();
+    last_KF->getOPtr()->fix();
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - (Eigen::Vector4s()<<0,0,0,1).finished()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+/* Introduce a perturbation in Origin_KF velocity and fix the last KF. 
+ * Ideally the optimization should be able to make origin_KF velocity converge to its correct value (value it would have taken if it had not been perturbated). 
+ * 
+ * TEST PASSED
+ */
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbatePositionOrigin_fixLastPQV)
+{
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    // velocity is modified : due to bias non initialized and noises. And due to motion constraint and fixing KF1's Position, velocity is used to satisfy conditions
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 ) ) <<
+    "last_KF velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*10)) <<
+    "last_KF position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100)) <<
+    "last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+
+    //===================================================== END{PROCESS DATA}
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+    
+    for (int i = 0 ; i < 3 ; i++)
+    {
+        for (int j = 0 ; j < 3 ; j++)
+        {
+            for (int k = 1 ; k < 3 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 1.0;
+                perturbated_state(j) += 1.0;
+                perturbated_state(k) += 1.0;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (origin_state_afterCeres.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "origin_state_afterCeres position state : " << origin_state_afterCeres.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (origin_state_afterCeres.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres quaternion : " << origin_state_afterCeres.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+
+    //===================================================== END{SOLVER PART}
+}
+
+/* Introduce a perturbation in Origin_KF velocity and fix the last KF. 
+ * Ideally the optimization should be able to make origin_KF velocity converge to its correct value (value it would have taken if it had not been perturbated). 
+ * 
+ * TEST PASSED
+ */
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateVelocityOrigin_fixLastPQV)
+{
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    // velocity is modified : due to bias non initialized and noises. And due to motion constraint and fixing KF1's Position, velocity is used to satisfy conditions
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 ) ) <<
+    "last_KF velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*10)) <<
+    "last_KF position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100)) <<
+    "last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+
+    //===================================================== END{PROCESS DATA}
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+    
+    for (int i = 7 ; i < 10 ; i++)
+    {
+        for (int j = 7 ; j < 10 ; j++)
+        {
+            for (int k = 7 ; k < 10 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 1.0;
+                perturbated_state(j) += 2.0;
+                perturbated_state(k) += 3.0;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state); //should not be needed sincce we fixed this KF
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //Velocity estimation depends on bias estimation.
+                //EXPECT_TRUE( (origin_state_afterCeres.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ) ) <<
+                //"origin_state_afterCeres velocity state : " << origin_state_afterCeres.segment(7,3).transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (origin_state_afterCeres.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres position state : " << origin_state_afterCeres.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (origin_state_afterCeres.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres quaternion : " << origin_state_afterCeres.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+
+    // COMPUTE COVARIANCES
+    //std::cout << "\t\t\t ______computing covariances______" << std::endl;
+    //ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+    //std::cout << "\t\t\t ______computed!______" << std::endl;
+
+    //===================================================== END{SOLVER PART}
+}
+
+/* Introduce a perturbation in Origin_KF orientation and fix the last KF. 
+ * Ideally the optimization should be able to make origin_KF velocity converge to its correct value (value it would have taken if it had not been perturbated). 
+ * Origin_KF is unfixed. Last_KF is fixed.
+ * 
+ * TEST PASSED
+ */
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateOrientationOrigin_fixLastPQV)
+{
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+    origin_KF->unfix();
+    
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    // velocity is modified : due to bias non initialized and noises. And due to motion constraint and fixing KF1's Position, velocity is used to satisfy conditions
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 ) ) <<
+    "last_KF velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*10)) <<
+    "last_KF position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100)) <<
+    "last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+
+    //===================================================== END{PROCESS DATA}
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_state.data() + 3);
+
+    
+    for (int i = 0 ; i < 3 ; i++)
+    {
+        for (int j = 0 ; j < 3 ; j++)
+        {
+            for (int k = 0 ; k < 3 ; k++)
+            {
+                Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+                orientation_perturbation(0) += i*0.2;
+                orientation_perturbation(1) += j*0.1;
+                orientation_perturbation(2) += k*0.15;
+
+                perturbated_state = initial_origin_state;
+                quat_map = quat_map * v2q(orientation_perturbation);
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                //depends on other estimations, ex: bias
+                //EXPECT_TRUE( (origin_state_afterCeres.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 ) ) << "iteration " << i<<"."<<j<<"."<<k <<
+                //"\norigin_state_afterCeres velocity state : " << origin_state_afterCeres.segment(7,3).transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (origin_state_afterCeres.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres position state : " << origin_state_afterCeres.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (origin_state_afterCeres.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres quaternion : " << origin_state_afterCeres.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+    //===================================================== END{SOLVER PART}
+}
+
+
+/* Introduce a perturbation in Origin_KF orientation and fix the last KF. 
+ * Ideally the optimization should be able to make origin_KF velocity converge to its correct value (value it would have taken if it had not been perturbated). 
+ * Origin_KF is unfixed. Last_KF is fixed.
+ * 
+ * TEST PASSED
+ */
+
+ TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateAccBiasOrigin_fixLastPQV)
+{
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    // velocity is modified : due to bias non initialized and noises. And due to motion constraint and fixing KF1's Position, velocity is used to satisfy conditions
+    EXPECT_FALSE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 ) ) <<
+    "last_KF velocity state : " << last_KF->getVPtr()->getState().transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*10)) <<
+    "last_KF position state : " << last_KF->getPPtr()->getState().transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100)) <<
+    "last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+
+    //===================================================== END{PROCESS DATA}
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+    
+    for (int i = 10 ; i < 13 ; i++)
+    {
+        for (int j = 10 ; j < 13 ; j++)
+        {
+            for (int k = 10 ; k < 13 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 1.0;
+                perturbated_state(j) += 1.0;
+                perturbated_state(k) += 1.0;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state); //should not be needed sincce we fixed this KF
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                // this will depend on bias estimation
+                //EXPECT_TRUE( (origin_state_afterCeres.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 ) ) <<
+                //"origin_state_afterCeres velocity state : " << origin_state_afterCeres.segment(7,3).transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (origin_state_afterCeres.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres position state : " << origin_state_afterCeres.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                ASSERT_TRUE( (origin_state_afterCeres.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "origin_state_afterCeres quaternion : " << origin_state_afterCeres.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (origin_state_afterCeres.segment(10,3) - origin_imuKF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, 0.00001 )) <<
+                "origin_state_afterCeres acc bias : " << origin_state_afterCeres.segment(10,3).transpose() << "\n origin acc bias state : " << origin_imuKF->getAccBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+    //===================================================== END{SOLVER PART}
+}
+
+/* Introduce a perturbation in Origin_KF
+ * Ideally the optimization should be able to make origin_KF position converge to its correct value (value it would have taken if it had not been perturbated). 
+ * 
+ * Quaternion error depends on the perturbation that was introduced.
+ */
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbatePositionOrigin_UnfixPerturbatedOnly) //GOING WRONG : Bias estimation depends on motion with real data
+{
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    //Unfix only StateBlcok of interest
+    last_KF->fix();
+    origin_KF->fix();
+    origin_KF->getPPtr()->unfix();
+    //===================================================== END{PROCESS DATA}
+
+    wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+    
+    for (int i = 0 ; i < 3 ; i++)
+    {
+        for (int j = 0 ; j < 3 ; j++)
+        {
+            for (int k = 1 ; k < 3 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 1.0;
+                perturbated_state(j) += 1.0;
+                perturbated_state(k) += 1.0;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (origin_state_afterCeres.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "origin_state_afterCeres position state : " << origin_state_afterCeres.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+
+    //===================================================== END{SOLVER PART}
+}
+
+/* Introduce a perturbation in Origin_KF
+ * Ideally the optimization should be able to make origin_KF velocity converge to its correct value (value it would have taken if it had not been perturbated). 
+ * 
+ * The perturbated StateBlock is the only one unfixed in this test.
+ * Error in velocity StateBlock is in 1e-4
+ */
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateVelocityOrigin_UnfixPerturbatedOnly)
+{
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+
+    //Unfix only StateBlock of interest
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+    origin_KF->fix();
+    origin_KF->getVPtr()->unfix();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    //===================================================== END{PROCESS DATA}
+    
+    for (int i = 7 ; i < 10 ; i++)
+    {
+        for (int j = 7 ; j < 10 ; j++)
+        {
+            for (int k = 7 ; k < 10 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 1.0;
+                perturbated_state(j) += 2.0;
+                perturbated_state(k) += 3.0;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (origin_state_afterCeres.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, 0.001 ) ) <<
+                "origin_state_afterCeres velocity state : " << origin_state_afterCeres.segment(7,3).transpose() << "\n origin velocity : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+    //===================================================== END{SOLVER PART}
+}
+
+/* Introduce a perturbation in Origin_KF
+ * Ideally the optimization should be able to make origin_KF orientation converge to its correct value (value it would have taken if it had not been perturbated). 
+ * 
+ * The perturbated StateBlock is the only one unfixed in this test.
+ */
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateOrientationOrigin_UnfixPerturbatedOnly)
+{
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    last_KF->getOPtr()->fix();
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(initial_origin_state);
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbated_state.data() + 3);
+
+    //unfix only StateBlock of interest
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+    origin_imuKF->fix();
+    origin_imuKF->getAccBiasPtr()->unfix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    origin_KF->fix();
+    origin_KF->getOPtr()->unfix();
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    //===================================================== END{PROCESS DATA}
+    
+    for (int i = 0 ; i < 3 ; i++)
+    {
+        for (int j = 0 ; j < 3 ; j++)
+        {
+            for (int k = 0 ; k < 3 ; k++)
+            {
+                Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+                orientation_perturbation(0) += i*0.2;
+                orientation_perturbation(1) += j*0.1;
+                orientation_perturbation(2) += k*0.15;
+
+                perturbated_state = initial_origin_state;
+                quat_map = quat_map * v2q(orientation_perturbation);
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (origin_state_afterCeres.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, 0.0001 )) <<
+                "origin_state_afterCeres quaternion : " << origin_state_afterCeres.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+
+    //===================================================== END{SOLVER PART}
+}
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateAccBiasOrigin_UnfixPerturbatedOnly)
+{
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+
+    //Unfix only StateBlock of interest
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+    origin_KF->fix();
+    origin_imuKF->getAccBiasPtr()->unfix();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    //===================================================== END{PROCESS DATA}
+    
+    for (int i = 10 ; i < 13 ; i++)
+    {
+        for (int j = 10 ; j < 13 ; j++)
+        {
+            for (int k = 10 ; k < 13 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 1.0;
+                perturbated_state(j) += 2.0;
+                perturbated_state(k) += 3.0;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (origin_state_afterCeres.segment(10,3) - origin_imuKF->getAccBiasPtr()->getState()).isMuchSmallerThan(1,0.001 ) ) <<
+                "origin_state_afterCeres acc_bias state : " << origin_state_afterCeres.segment(10,3).transpose() << "\n origin acc_bias : " << origin_imuKF->getAccBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_2s_move_PerturbateGyroBiasOrigin_UnfixPerturbatedOnly)
+{
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    std::string filepath_string(wolf_root + "/src/test/data/IMU/imu_plateform_2s.txt");
+    imu_filepath   = new char[filepath_string.length() + 1];
+    std::strcpy(imu_filepath, filepath_string.c_str());
+    std::ifstream imu_data_input;
+
+    imu_data_input.open(imu_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+
+    while( !imu_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    //IMU data have all been processed. Now we process the odom3D data
+    // PROCESS ODOM 3D DATA
+    mot_ptr->setTimeStamp(ts);
+    mot_ptr->setData(data_odom3D);
+    sen_odom3D->process(mot_ptr);
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    Eigen::VectorXs initial_final_state(16);
+    initial_final_state = last_KF->getState();
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbated_state(16);
+
+    //Unfix only StateBlock of interest
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+    last_KF->getGyroBiasPtr()->unfix();
+    origin_KF->fix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+
+    // call solver to get values after optimization. Wemwill compare the following output to these
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    Eigen::VectorXs origin_state_afterCeres(16);
+    origin_state_afterCeres = origin_KF->getState();
+
+    //===================================================== END{PROCESS DATA}
+    
+    for (int i = 13 ; i < 16 ; i++)
+    {
+        for (int j = 13 ; j < 16 ; j++)
+        {
+            for (int k = 13 ; k < 16 ; k++)
+            {
+                perturbated_state = initial_origin_state;
+                perturbated_state(i) += 0.2;
+                perturbated_state(j) += 0.15;
+                perturbated_state(k) += 0.3;
+
+                origin_KF->setState(perturbated_state);
+                last_KF->setState(initial_final_state);
+
+                //===================================================== SOLVER PART
+     
+                summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (origin_state_afterCeres.segment(13,3) - origin_imuKF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, 0.00001 ) ) <<
+                "origin_state_afterCeres gyro_bias state : " << origin_state_afterCeres.segment(13,3).transpose() << "\n origin gyro_bias : " << origin_imuKF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests,Plateform_10s_move_fixOriginPQ)
+{
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    char* imu_filepath;
+    char* odom_filepath;
+    std::string imu_filepath_string(wolf_root + "/src/test/data/IMU/imu_plateforme_10s.txt");
+    std::string odom_filepath_string(wolf_root + "/src/test/data/IMU/odom_plateforme_10s.txt");
+    imu_filepath   = new char[imu_filepath_string.length() + 1];
+    odom_filepath   = new char[odom_filepath_string.length() + 1];
+    std::strcpy(imu_filepath, imu_filepath_string.c_str());
+    std::strcpy(odom_filepath, odom_filepath_string.c_str());
+    std::ifstream imu_data_input;
+    std::ifstream odom_data_input;
+
+    imu_data_input.open(imu_filepath);
+    odom_data_input.open(odom_filepath);
+    WOLF_INFO("imu file: ", imu_filepath)
+    if(!imu_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //prepare creation of file if DEBUG_RESULTS activated
+    #ifdef DEBUG_RESULTS
+        std::ofstream debug_results;
+        debug_results.open("debug_results.dat");
+        if(debug_results)
+            debug_results << "%%TimeStamp\t"
+                        << "dp_x\t" << "dp_y\t" << "dp_z\t" << "dq_x\t" << "dq_y\t" << "dq_z\t" << "dq_w\t" << "dv_x\t" << "dv_y\t" << "dv_z\t"
+                        << "Dp_x\t" << "Dp_y\t" << "Dp_z\t" << "Dq_x\t" << "Dq_y\t" << "Dq_z\t" << "Dq_w\t" << "Dv_x\t" << "Dv_y\t" << "Dv_z\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t" << std::endl;
+    #endif
+
+
+    //===================================================== SETTING PROBLEM
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    FrameIMUPtr origin_imuKF = std::static_pointer_cast<FrameIMU>(origin_KF);
+
+    origin_imuKF->getPPtr()->fix();
+    origin_imuKF->getOPtr()->fix();
+
+    origin_imuKF->getAccBiasPtr()->unfix();
+    origin_imuKF->getGyroBiasPtr()->unfix();
+    
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,-0.06,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0), ts_odom(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+    odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5]; //Ax, Ay, Az, Gx, Gy, Gz
+    ts_odom.set(input_clock);
+
+    while( !imu_data_input.eof() || !odom_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+
+        if(ts.get() == ts_odom.get())
+        {
+            // PROCESS ODOM 3D DATA
+            mot_ptr->setTimeStamp(ts_odom);
+            mot_ptr->setData(data_odom3D);
+            sen_odom3D->process(mot_ptr);
+
+            odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5]; //Ax, Ay, Az, Gx, Gy, Gz
+            ts_odom.set(input_clock);
+        }
+    }
+
+    //closing file
+    imu_data_input.close();
+
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    //Check and print wolf tree
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.FullReport() << std::endl;
+    
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    data_odom3D << 0,-0.06,0, 0,0,0;
+    //test last against origin
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - data_odom3D.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+    "last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 ));
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+//___________________________________________
+// PLATEFORM TESTS BIS - simulated data
+//___________________________________________
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, No_Perturbation)
+{
+    origin_KF->fix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+    
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    ASSERT_TRUE( (expected_final_state.head(3) - last_KF->getPPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*10 ) ) <<
+    "expected_final_state position : " << expected_final_state.head(3).transpose() << "\n last_KF position : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.segment(3,4) - last_KF->getOPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS ) ) <<
+    "expected_final_state quaternion : " << expected_final_state.segment(3,4).transpose() << "\n last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.tail(3) - last_KF->getVPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*10) ) <<
+    "expected_final_state velocity : " << expected_final_state.tail(3).transpose() << "\n last_KF velocity : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+
+    last_KF->unfix();
+    last_KF->getAccBiasPtr()->fix();
+    last_KF->getGyroBiasPtr()->fix();
+
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+    Eigen::MatrixXs cov3(Eigen::Matrix3s::Zero());
+    /*Eigen::MatrixXs cov4(Eigen::Matrix4s::Zero());
+
+    wolf_problem_ptr_->getCovarianceBlock(last_KF->getPPtr(), last_KF->getPPtr(), cov3);
+    std::cout << "\n last_KF position covariance : \n" << cov3 << std::endl;
+    wolf_problem_ptr_->getCovarianceBlock(last_KF->getOPtr(), last_KF->getOPtr(), cov4);
+    std::cout << "\n last_KF orientation covariance : \n" << cov4 << std::endl;*/
+    wolf_problem_ptr_->getCovarianceBlock(last_KF->getVPtr(), last_KF->getVPtr(), cov3);
+    //std::cout << "\n last_KF velocity covariance : \n" << cov3 << std::endl;
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginPosition_UnfixPertubedOnly)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+    origin_KF->getPPtr()->unfix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getAccBiasPtr()->fix();
+    origin_KF->getGyroBiasPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 0 ; i < 3 ; i++)
+    {
+        for (int j = 0 ; j < 3 ; j++)
+        {
+            for (int k = 1 ; k < 3 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.05; //variation between 5 cm and 15 cm
+                perturbed_state(j) += 0.05;
+                perturbed_state(k) += 0.05;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginVelocity_UnfixPertubedOnly)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    last_KF->fix();
+
+    // fix / unfix StateBlocks
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->unfix();
+    origin_KF->getAccBiasPtr()->fix();
+    origin_KF->getGyroBiasPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 7 ; i < 10 ; i++)
+    {
+        for (int j = 7 ; j < 10 ; j++)
+        {
+            for (int k = 7 ; k < 10 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5;
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state position state : " << initial_origin_state.segment(7,3).transpose() << "\n origin position state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginOrientation_UnfixPertubedOnly)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->unfix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getAccBiasPtr()->fix();
+    origin_KF->getGyroBiasPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbed_state.data() + 3);
+    
+    for (int i = 7 ; i < 10 ; i++)
+    {
+        for (int j = 7 ; j < 10 ; j++)
+        {
+            for (int k = 7 ; k < 10 ; k++)
+            {
+                Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+                orientation_perturbation(0) += i*0.2;
+                orientation_perturbation(1) += j*0.1;
+                orientation_perturbation(2) += k*0.15;
+
+                perturbed_state = initial_origin_state;
+                quat_map = quat_map * v2q(orientation_perturbation);
+
+                origin_KF->setState(perturbed_state);
+
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                ASSERT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginAccBias_UnfixPertubedOnly)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getAccBiasPtr()->unfix();
+    origin_KF->getGyroBiasPtr()->fix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 10 ; i < 13 ; i++)
+    {
+        for (int j = 10 ; j < 13 ; j++)
+        {
+            for (int k = 10 ; k < 13 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5;
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state position state : " << initial_origin_state.segment(10,3).transpose() << "\n origin position state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginGyroBias_UnfixPertubedOnly)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    origin_KF->getAccBiasPtr()->fix();
+    origin_KF->getGyroBiasPtr()->unfix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 13 ; i < 16 ; i++)
+    {
+        for (int j = 13 ; j < 16 ; j++)
+        {
+            for (int k = 13 ; k < 16 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5;
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state position state : " << initial_origin_state.tail(3).transpose() << "\n origin position state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginPosition_UnfixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 0 ; i < 3 ; i++)
+    {
+        for (int j = 0 ; j < 3 ; j++)
+        {
+            for (int k = 1 ; k < 3 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5; //variation between 5 cm and 15 cm
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state velocity state : " << initial_origin_state.segment(7,3).transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state acc bias state : " << initial_origin_state.segment(10,3).transpose() << "\n origin acc bias state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state gyro bias state : " << initial_origin_state.tail(3).transpose() << "\n origin gyro bias state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginVelocity_UnfixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 7 ; i < 10 ; i++)
+    {
+        for (int j = 7 ; j < 10 ; j++)
+        {
+            for (int k = 7 ; k < 10 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5; //variation between 5 cm and 15 cm
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state velocity state : " << initial_origin_state.segment(7,3).transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state acc bias state : " << initial_origin_state.segment(10,3).transpose() << "\n origin acc bias state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state gyro bias state : " << initial_origin_state.tail(3).transpose() << "\n origin gyro bias state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginOrientation_UnfixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbed_state.data() + 3);
+    
+    for (int i = 7 ; i < 10 ; i++)
+    {
+        for (int j = 7 ; j < 10 ; j++)
+        {
+            for (int k = 7 ; k < 10 ; k++)
+            {
+                Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+                orientation_perturbation(0) += i*0.2;
+                orientation_perturbation(1) += j*0.1;
+                orientation_perturbation(2) += k*0.15;
+
+                perturbed_state = initial_origin_state;
+                quat_map = quat_map * v2q(orientation_perturbation);
+
+                origin_KF->setState(perturbed_state);
+
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state velocity state : " << initial_origin_state.segment(7,3).transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state acc bias state : " << initial_origin_state.segment(10,3).transpose() << "\n origin acc bias state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state gyro bias state : " << initial_origin_state.tail(3).transpose() << "\n origin gyro bias state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginAccBias_UnfixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 10 ; i < 13 ; i++)
+    {
+        for (int j = 10 ; j < 13 ; j++)
+        {
+            for (int k = 10 ; k < 13 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5;
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state velocity state : " << initial_origin_state.segment(7,3).transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state acc bias state : " << initial_origin_state.segment(10,3).transpose() << "\n origin acc bias state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state gyro bias state : " << initial_origin_state.tail(3).transpose() << "\n origin gyro bias state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginGyroBias_UnfixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    
+    for (int i = 13 ; i < 16 ; i++)
+    {
+        for (int j = 13 ; j < 16 ; j++)
+        {
+            for (int k = 13 ; k < 16 ; k++)
+            {
+                perturbed_state = initial_origin_state;
+                perturbed_state(i) += 0.5;
+                perturbed_state(j) += 0.5;
+                perturbed_state(k) += 0.5;
+
+                origin_KF->setState(perturbed_state);
+                //last_KF is fixed. There is no need to reinitialize its state
+                //===================================================== SOLVER PART
+     
+                ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+                //std::cout << summary.BriefReport() << std::endl;
+
+                EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+                "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state velocity state : " << initial_origin_state.segment(7,3).transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+                "initial_origin_state acc bias state : " << initial_origin_state.segment(10,3).transpose() << "\n origin acc bias state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+                EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+                "initial_origin_state gyro bias state : " << initial_origin_state.tail(3).transpose() << "\n origin gyro bias state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+            }
+        }
+    }
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbOriginAll_UnfixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    // fix / unfix StateBlocks
+    last_KF->fix();
+    origin_KF->unfix();
+
+    Eigen::VectorXs initial_origin_state = origin_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbed_state.data() + 3);
+    
+    perturbed_state = initial_origin_state;
+    perturbed_state(0) += 1.5;
+    perturbed_state(1) += 1.0;
+    perturbed_state(2) += 1.25;
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    orientation_perturbation(0) += 0.6;
+    orientation_perturbation(1) += 0.5;
+    orientation_perturbation(2) += -0.15;
+    quat_map = quat_map * v2q(orientation_perturbation);
+
+    perturbed_state(7) += 1.5;
+    perturbed_state(8) += 0.7;
+    perturbed_state(9) += 1.15;
+
+    perturbed_state(10) += 0.75;
+    perturbed_state(11) += 1.0;
+    perturbed_state(12) += 0.6;
+    perturbed_state(13) += 0.55;
+    perturbed_state(14) += 0.42;
+    perturbed_state(15) += 0.035;
+
+    origin_KF->setState(perturbed_state);
+    //last_KF is fixed. There is no need to reinitialize its state
+
+    //===================================================== SOLVER PART
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    EXPECT_TRUE( (initial_origin_state.head(3) - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "initial_origin_state position state : " << initial_origin_state.head(3).transpose() << "\n origin position state : " << origin_KF->getPPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_origin_state.segment(3,4) - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+    "initial_origin_state quaternion : " << initial_origin_state.segment(3,4).transpose() << "\n origin quaternion state : " << origin_KF->getOPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_origin_state.segment(7,3) - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "initial_origin_state velocity state : " << initial_origin_state.segment(7,3).transpose() << "\n origin velocity state : " << origin_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_origin_state.segment(10,3) - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "initial_origin_state acc bias state : " << initial_origin_state.segment(10,3).transpose() << "\n origin acc bias state : " << origin_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_origin_state.tail(3) - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "initial_origin_state gyro bias state : " << initial_origin_state.tail(3).transpose() << "\n origin gyro bias state : " << origin_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, FixOriginPQV_UnfixLast)
+{
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    ASSERT_TRUE( (expected_final_state.head(3) - last_KF->getPPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*100 ) ) <<
+    "expected_final_state position : " << expected_final_state.head(3).transpose() << "\n last_KF position : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.segment(3,4) - last_KF->getOPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*100 ) ) <<
+    "expected_final_state quaternion : " << expected_final_state.segment(3,4).transpose() << "\n last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.tail(3) - last_KF->getVPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*1000) ) <<
+    "expected_final_state velocity : " << expected_final_state.tail(3).transpose() << "\n last_KF velocity : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, FixOriginPQV_UnfixLast_fixlastP)
+{
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->unfix();
+    last_KF->getPPtr()->fix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    //ASSERT_TRUE( (expected_final_state.head(3) - last_KF->getPPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*100 ) ) <<
+    //"expected_final_state position : " << expected_final_state.head(3).transpose() << "\n last_KF position : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.segment(3,4) - last_KF->getOPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*100 ) ) <<
+    "expected_final_state quaternion : " << expected_final_state.segment(3,4).transpose() << "\n last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.tail(3) - last_KF->getVPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*1000) ) <<
+    "expected_final_state velocity : " << expected_final_state.tail(3).transpose() << "\n last_KF velocity : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, FixOriginPQV_UnfixLast_fixlastQ)
+{
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->unfix();
+    last_KF->getOPtr()->fix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    ASSERT_TRUE( (expected_final_state.head(3) - last_KF->getPPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS ) ) <<
+    "expected_final_state position : " << expected_final_state.head(3).transpose() << "\n last_KF position : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.tail(3) - last_KF->getVPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS) ) <<
+    "expected_final_state velocity : " << expected_final_state.tail(3).transpose() << "\n last_KF velocity : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, FixOriginPQV_UnfixLast_fixlastV)
+{
+    origin_KF->unfix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+    last_KF->unfix();
+    last_KF->getPPtr()->fix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    ASSERT_TRUE( (expected_final_state.head(3) - last_KF->getPPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*100 ) ) <<
+    "expected_final_state position : " << expected_final_state.head(3).transpose() << "\n last_KF position : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (expected_final_state.segment(3,4) - last_KF->getOPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*100 ) ) <<
+    "expected_final_state quaternion : " << expected_final_state.segment(3,4).transpose() << "\n last_KF quaternion : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+    //ASSERT_TRUE( (expected_final_state.tail(3) - last_KF->getVPtr()->getState()).isMuchSmallerThan(1,wolf::Constants::EPS*1000) ) <<
+    //"expected_final_state velocity : " << expected_final_state.tail(3).transpose() << "\n last_KF velocity : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+TEST_F(ProcessorIMU_Odom_tests_plateform_simulation, PerturbLastAll_UnfixLast_fixOrigin)
+{
+    origin_KF->fix();
+    last_KF->unfix();
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+
+    Eigen::VectorXs initial_final_state = last_KF->getState();
+    Eigen::VectorXs perturbed_state(16);
+    Eigen::Map<Eigen::Quaternions> quat_map(perturbed_state.data() + 3);
+    
+    perturbed_state = initial_final_state;
+    perturbed_state(0) += 1.5;
+    perturbed_state(1) += 1.0;
+    perturbed_state(2) += 1.25;
+
+    Eigen::Vector3s orientation_perturbation((Eigen::Vector3s()<<0,0,0).finished());
+    orientation_perturbation(0) += 0.6;
+    orientation_perturbation(1) += 0.5;
+    orientation_perturbation(2) += -0.15;
+    quat_map = quat_map * v2q(orientation_perturbation);
+
+    perturbed_state(7) += 1.5;
+    perturbed_state(8) += 0.7;
+    perturbed_state(9) += 1.15;
+
+    perturbed_state(10) += 0.75;
+    perturbed_state(11) += 1.0;
+    perturbed_state(12) += 0.6;
+    perturbed_state(13) += 0.55;
+    perturbed_state(14) += 0.42;
+    perturbed_state(15) += 0.035;
+
+    last_KF->setState(perturbed_state);
+
+    //===================================================== SOLVER PART
+    summary = ceres_manager_wolf_diff->solve();
+    //std::cout << summary.BriefReport() << std::endl;
+
+    EXPECT_TRUE( (initial_final_state.head(3) - last_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "initial_final_state position state : " << initial_final_state.head(3).transpose() << "\n last position state : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_final_state.segment(3,4) - last_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*10 )) <<
+    "initial_final_state quaternion : " << initial_final_state.segment(3,4).transpose() << "\n last quaternion state : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_final_state.segment(7,3) - last_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "initial_final_state velocity state : " << initial_final_state.segment(7,3).transpose() << "\n last velocity state : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_final_state.segment(10,3) - last_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS*100 )) <<
+    "initial_final_state acc bias state : " << initial_final_state.segment(10,3).transpose() << "\n last acc bias state : " << last_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (initial_final_state.tail(3) - last_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "initial_final_state gyro bias state : " << initial_final_state.tail(3).transpose() << "\n last gyro bias state : " << last_KF->getGyroBiasPtr()->getState().transpose() << std::endl;
+
+    //wolf_problem_ptr_->print(4,1,1,1);
+}
+
+//___________________________________________
+// END{ PLATEFORM TESTS BIS - simulated data }
+//___________________________________________
+
+//_______________________________________________________________________________________________________________
+// END ##################################### Plateform TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+//_______________________________________________________________________________________________________________
+// ##################################### Imperfect IMU TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+TEST_F(ProcessorIMU_Odom_tests, IMU_Biased)
+{
+
+    /* In this scenario, we simulate the integration of a static IMU biased in X Acceleration and we add an odometry measurement.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same and the bias to be identified correctly.
+     * Origin KeyFrame is fixed
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1
+     *     \____constraintOdom3D___/
+     *
+     * a first test to check that bias is correctly used in state reconstruction
+     */
+
+     //===================================================== END OF SETTINGS
+
+     // set origin of processorMotions
+     Vector6s imuBias((Eigen::Vector6s() << 0.01, 0.005, 0.015, 0.05, 0.014, 0.1).finished() );
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, imuBias(0),imuBias(1),imuBias(2), imuBias(3),imuBias(4),imuBias(5)).finished());
+    t.set(0);
+
+    FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+    //===================================================== END{END OF SETTINGS}
+
+    //===================================================== PROCESS DATA
+
+    // PROCESS IMU DATA
+
+    Eigen::Vector6s data;
+    data << 0.0, 0.0, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+    data += imuBias; //Biased IMU
+    Scalar dt = t.get();
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+    while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()) ){
+
+        // Time and data variables
+        dt += 0.001;
+        ts.set(dt);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    // PROCESS ODOM 3D DATA
+    Eigen::Vector6s data_odom3D;
+    data_odom3D << 0,0,0, 0,0,0;
+    
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+    sen_odom3D->process(mot_ptr);
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "origin_KF position : " << origin_KF->getPPtr()->getState().transpose() << "\n last_KF position : " << last_KF->getPPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "origin_KF orientation : " << origin_KF->getOPtr()->getState().transpose() << "\n last_KF orientation : " << last_KF->getOPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "origin_KF velocity : " << origin_KF->getVPtr()->getState().transpose() << "\n last_KF velocity : " << last_KF->getVPtr()->getState().transpose() << std::endl;
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - imuBias.head(3)).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - imuBias.tail(3)).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+    //===================================================== END{SOLVER PART}
+}
+
+TEST_F(ProcessorIMU_Odom_tests, IMU_Biased_perturbData)
+{
+
+    /* In this scenario, we simulate the integration of a static IMU biased in X Acceleration and we add an odometry measurement.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same and the bias to be identified correctly.
+     * Origin KeyFrame is fixed
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1
+     *     \____constraintOdom3D___/
+     *
+     * Add a small bias perturbation in imu data before it is processed by the capture.
+     * Expect this small increment to be corrected in the bias StateBlock of the generated KeyFrame.
+     */
+
+     //===================================================== END OF SETTINGS
+
+     // set origin of processorMotions
+     Vector6s imuBias((Eigen::Vector6s() << 0.01, 0.005, 0.015, 0.05, 0.014, 0.1).finished() );
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, imuBias(0),imuBias(1),imuBias(2), imuBias(3),imuBias(4),imuBias(5)).finished());
+    t.set(0);
+
+    FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+    //===================================================== END{END OF SETTINGS}
+
+    //===================================================== PROCESS DATA
+
+    // PROCESS IMU DATA
+
+    Eigen::Vector6s data;
+    data << 0.0, 0.0, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+    data += imuBias; //Biased IMU
+
+    Eigen::Vector6s imuBias_perturb((Eigen::Vector6s() << 0.001, 0, 0, 0, 0, 0).finished() );
+    data += imuBias_perturb;
+    Scalar dt = t.get();
+    TimeStamp ts(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+    while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()) ){
+
+        // Time and data variables
+        dt += 0.001;
+        ts.set(dt);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    // PROCESS ODOM 3D DATA
+    Eigen::Vector6s data_odom3D;
+    data_odom3D << 0,0,0, 0,0,0;
+    
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+    sen_odom3D->process(mot_ptr);
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    // Perturb bias before calling the solver
+
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    origin_KF->fix();
+    origin_KF->getAccBiasPtr()->unfix();
+    last_KF->fix();
+    last_KF->getAccBiasPtr()->unfix();
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+    
+    // IMU data was perturbed. We expect the bias of last_KF to have changed due to this perturbation
+    EXPECT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "origin_KF Acc bias : " << origin_KF->getAccBiasPtr()->getState().transpose() << "\n last_KF Acc bias : " << last_KF->getAccBiasPtr()->getState().transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getAccBiasPtr()->getState() - (imuBias.head(3) + imuBias_perturb.head(3))).isMuchSmallerThan(1, wolf::Constants::EPS )) <<
+    "last_KF Acc bias :" << last_KF->getAccBiasPtr()->getState().transpose() << "\n  expected Acc bias : " << (imuBias.head(3) + imuBias_perturb.head(3)).transpose() << std::endl;
+    EXPECT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    EXPECT_TRUE( (last_KF->getGyroBiasPtr()->getState() - (imuBias.tail(3) + imuBias_perturb.tail(3))).isMuchSmallerThan(1, wolf::Constants::EPS ));
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+//_______________________________________________________________________________________________________________
+// END ##################################### Imperfect IMU TESTS #####################################
+//_______________________________________________________________________________________________________________
+
+
+TEST_F(ProcessorIMU_Odom_tests, static_Optim_IMUOdom_nKFs_biasUnfixed)
+{
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving and we add an odometry measurement.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same
+     * Origin KeyFrame is fixed
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1 ---- constraintIMU ---- KF2 ---- (. . . . . .) ---- KFn
+     *     \____________________________________constraintOdom3D___________________________/
+     *
+     * IMU BIAS UNFIXED
+     *
+     * With IMU data only, biases are not observable ! So covariance cannot be computed due to jacobian rank deficiency.
+     * We must add an odometry to make covariances computable
+     */
+     
+    //===================================================== END OF SETTINGS
+
+    // set origin of processorMotions
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+    t.set(0);
+
+    FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+    //There should be 3 captures at origin_frame : CaptureOdom, captureIMU
+    EXPECT_EQ((wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front())->getCaptureList().size(),2);
+    ASSERT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isKey()) << "origin_frame is not a KeyFrame..." << std::endl;
+
+    //===================================================== END{END OF SETTINGS}
+
+    //===================================================== PROCESS DATA
+    // PROCESS IMU DATA
+
+    Eigen::Vector6s data;
+
+    data << 0.00, 0.000, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+    Scalar dt = t.get();
+    TimeStamp ts(0.001);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+    while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()*number_of_KF) ){
+        
+        // Time and data variables
+        dt += 0.001;
+        ts.set(dt);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    // PROCESS ODOM 3D DATA
+    Eigen::Vector6s data_odom3D;
+    data_odom3D << 0,0,0, 0,0,0;
+    
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+    sen_odom3D->process(mot_ptr);
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+TEST_F(ProcessorIMU_Odom_tests, static_Optim_IMUOdom_nKFs_biasFixed)
+{
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving and we add an odometry measurement.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same
+     * Origin KeyFrame is fixed
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1 ---- constraintIMU ---- KF2 ---- (. . . . . .) ---- KFn
+     *     \____________________________________constraintOdom3D___________________________/
+     *
+     * IMU BIAS UNFIXED
+     *
+     * With IMU data only, biases are not observable ! So covariance cannot be computed due to jacobian rank deficiency.
+     * We must add an odometry to make covariances computable
+     */
+
+    //===================================================== END OF SETTINGS
+
+    // set origin of processorMotions
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+    t.set(0);
+
+    FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+
+    //There should be 2 captures at origin_frame : CaptureOdom, captureIMU
+    EXPECT_EQ((wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front())->getCaptureList().size(),2);
+    ASSERT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isKey()) << "origin_frame is not a KeyFrame..." << std::endl;
+
+    //===================================================== END{END OF SETTINGS}
+
+    //===================================================== PROCESS DATA
+
+    // PROCESS IMU DATA
+
+    Eigen::Vector6s data;
+    data << 0.00, 0.000, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+    Scalar dt = t.get();
+    TimeStamp ts(0.001);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+
+    while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()*number_of_KF) ){
+        
+        // Time and data variables
+        dt += 0.001;
+        ts.set(dt);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+    }
+
+    // PROCESS ODOM 3D DATA
+    Eigen::Vector6s data_odom3D;
+    data_odom3D << 0,0,0, 0,0,0;
+    
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+    sen_odom3D->process(mot_ptr);
+
+        //Fix all biases StateBlocks
+    for(FrameBasePtr it : wolf_problem_ptr_->getTrajectoryPtr()->getFrameList()){
+        ( std::static_pointer_cast<FrameIMU>(it) )->getAccBiasPtr()->fix();
+        ( std::static_pointer_cast<FrameIMU>(it) )->getGyroBiasPtr()->fix();
+    }
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+     
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+
+    //===================================================== END{SOLVER PART}
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests, static_Optim_IMUOdom_SeveralKFs)
+{
+    /* In this scenario, we simulate the integration of a perfect IMU that is not moving and we add an odometry measurement.
+     * Initial State is [0,0,0, 0,0,0,1, 0,0,0] so we expect the Final State to be exactly the same
+     * Origin KeyFrame is fixed
+     * 
+     * Finally, we can represent the graph as :
+     *
+     *  KF0 ---- constraintIMU ---- KF1 ---- constraintIMU ---- KF2 ---- (. . . . . .) ---- KFn
+     *     \____constraintOdom3D___/   \____constraintOdom3D___/   \____constraintOdom3D___/
+     *
+     * data integration is done for 10s (10 * max_time_span)
+     * IMU data are processed at 1 Khz (every ms)
+     * Odom3D data are processed at 100 Hz (every 10 ms)
+     *
+     * With IMU data only, biases are not observable ! So covariance cannot be computed due to jacobian rank deficiency.
+     * We must add an odometry to make covariances computable
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+
+    //===================================================== END OF SETTINGS
+
+    // set origin of processorMotions
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+    t.set(0);
+
+    FrameBasePtr setOrigin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(setOrigin_KF);
+
+    wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+
+    //There should be 2 captures at origin_frame : CaptureOdom, captureIMU
+    EXPECT_EQ((wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front())->getCaptureList().size(),2);
+    ASSERT_TRUE(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->isKey()) << "origin_frame is not a KeyFrame..." << std::endl;
+
+    //===================================================== END{END OF SETTINGS}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data, data_odom3D;
+    data << 0.00, 0.000, -wolf::gravity()(2), 0.0, 0.0, 0.0;
+    data_odom3D << 0,0,0, 0,0,0;
+    Scalar dt = t.get();
+    TimeStamp ts(0.000);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(ts, sen_odom3D, data_odom3D, 6, 6);
+    wolf_problem_ptr_->setProcessorMotion(processor_ptr_imu);
+    unsigned int iter = 0;
+    const unsigned int odom_freq = 10; //processing odometry data every 10 ms
+
+    while( (dt-t.get()) < (std::static_pointer_cast<ProcessorIMU>(processor_ptr_)->getMaxTimeSpan()*number_of_KF) ){
+        
+        // PROCESS IMU DATA
+        // Time and data variables
+        dt += 0.001;
+        iter++;
+        ts.set(dt);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+
+        if(iter == odom_freq) //every 100 ms
+        {
+            // PROCESS ODOM 3D DATA
+            mot_ptr->setTimeStamp(ts);
+            mot_ptr->setData(data_odom3D);
+            sen_odom3D->process(mot_ptr);
+
+            iter = 0;
+        }
+    }
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    FrameIMUPtr origin_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front());
+    FrameIMUPtr last_KF = std::static_pointer_cast<FrameIMU>(wolf_problem_ptr_->getTrajectoryPtr()->closestKeyFrameToTimeStamp(ts));
+
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.BriefReport() << std::endl;
+
+    ASSERT_TRUE( (last_KF->getPPtr()->getState() - origin_KF->getPPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getOPtr()->getState() - origin_KF->getOPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getVPtr()->getState() - origin_KF->getVPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS ));
+    ASSERT_TRUE( (last_KF->getAccBiasPtr()->getState() - origin_KF->getAccBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+    ASSERT_TRUE( (last_KF->getGyroBiasPtr()->getState() - origin_KF->getGyroBiasPtr()->getState()).isMuchSmallerThan(1, wolf::Constants::EPS )); //because we simulate a perfect IMU
+
+    // COMPUTE COVARIANCES
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+    //===================================================== END{SOLVER PART}
+}
+
+
+TEST_F(ProcessorIMU_Odom_tests,Motion_IMU_and_Odom)
+{
+    /* In this test we will process both IMU and Odom3D data at the same time (in a same loop).
+     * we use data simulating a perfect IMU doing some motion. This motion could be a pure translation or a pure rotation or anything
+     *
+     * HOWEVER : The test will use 2 data files which shall meet the following requirements :
+     *
+     * - a file containing only imu data in IMU frame will be provided. IMU data shall be written in the form [ax, ay, az, wx, wy, wz].
+     *      The IMU measurements must include the measurement of the gravity.
+     *      First line of this file will contain the initial condition in position, orientation and velocity only. (PQV formulation)
+     *      Each line of the file correspond to a new set of IMU data.
+     *      Each data will be separated from the previous one with a tabulation (\t).
+     *      Finally, the following should give a clear idea of how the file is and summarizes the previous points :
+     *          (line1) px_initial\t   py_initial\t   pz_initial\t   qx_initial\t   qy_initial\t   qz_initial\t   qw_initial\t   vx_initial\t   vy_initial\t   vz_initial\t 
+     *          (line2) TimesTamp1\t   ax1\t   ay1\t   az1\t   wx1\t   wy1\t   wz1\t   
+     *          (line3) TimesTamp2\t   ax2\t   ay2\t   az2\t   wx2\t   wy2\t   wz2\t   
+     *          (.           .           .       .       .       .       .       .  )
+     *          (lineN) TimesTampN\t   axN\t   ayN\t   azN\t   wxN\t   wyN\t   wzN\t
+     *
+     * - a file containing only odometry measurements will be provided. This file only contains odometry in the form PO (using orientation vector here !)
+     *      Here is how the file should look like :
+     *          (line1) TimeStamp1\t    px1\t   py1\t   pz1\t   ox1\t   oy1\t   oz1
+     *          (line2) TimeStamp2\t    px2\t   py2\t   pz2\t   ox2\t   oy2\t   oz2
+     *          (   .         .           .       .       .       .       .       . )
+     *          (lineN) TimeStampN\t    pxN\t   pyN\t   pzN\t   oxN\t   oyN\t   ozN
+     *
+     *      TIMESTAMPS FROM IMU DATA FILE AND ODOM FILE MUST MATCH PERFECTLY !!!!
+     *      This does not mean that for each IMU data you must provide an odometry data !
+     *
+     *      Integration ends once the end of imu or odom data file is reached.
+     *
+     */
+
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+
+    std::ifstream imu_data_input;
+    std::ifstream odom_data_input;
+
+    imu_data_input.open(filename_motion_imu_data);
+    odom_data_input.open(filename_motion_odom);
+    WOLF_INFO("pure translation imu file: ", filename_motion_imu_data)
+    WOLF_INFO( "pure translation odom: ", filename_motion_odom)
+
+    if(!imu_data_input.is_open() || !odom_data_input.is_open()){
+        std::cerr << "Failed to open data files... Exiting" << std::endl;
+        ADD_FAILURE();
+    }
+
+    //prepare creation of file if DEBUG_RESULTS activated
+    #ifdef DEBUG_RESULTS
+        std::ofstream debug_results;
+        debug_results.open("debug_results.dat");
+        if(debug_results)
+            debug_results << "%%TimeStamp\t"
+                        << "dp_x\t" << "dp_y\t" << "dp_z\t" << "dq_x\t" << "dq_y\t" << "dq_z\t" << "dq_w\t" << "dv_x\t" << "dv_y\t" << "dv_z\t"
+                        << "Dp_x\t" << "Dp_y\t" << "Dp_z\t" << "Dq_x\t" << "Dq_y\t" << "Dq_z\t" << "Dq_w\t" << "Dv_x\t" << "Dv_y\t" << "Dv_z\t"
+                        << "X_x\t" << "X_y\t" << "X_z\t" << "Xq_x\t" << "Xq_y\t" << "Xq_z\t" << "Xq_w\t" << "Xv_x\t" << "Xv_y\t" << "Xv_z\t" << std::endl;
+    #endif
+
+
+    //===================================================== SETTING PROBLEM
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // reset origin of problem
+    Eigen::VectorXs x_origin((Eigen::Matrix<wolf::Scalar,16,1>()<<0,0,0, 0,0,0,1, 0,0,0, 0,0,0, 0,0,0).finished());
+
+    // initial conditions defined from data file
+    // remember that matlab's quaternion is W,X,Y,Z and the one in Eigen has X,Y,Z,W form
+    imu_data_input >> x_origin[0] >> x_origin[1] >> x_origin[2] >> x_origin[6] >> x_origin[3] >> x_origin[4] >> x_origin[5] >> x_origin[7] >> x_origin[8] >> x_origin[9];
+
+    t.set(0);
+    FrameBasePtr origin_KF = processor_ptr_imu->setOrigin(x_origin, t);
+    processor_ptr_odom3D->setOrigin(origin_KF);
+    //wolf_problem_ptr_->getTrajectoryPtr()->getFrameList().front()->fix();
+    origin_KF->getPPtr()->fix();
+    origin_KF->getOPtr()->fix();
+    origin_KF->getVPtr()->fix();
+
+    //===================================================== END{SETTING PROBLEM}
+
+    //===================================================== PROCESS DATA
+    // PROCESS DATA
+
+    Eigen::Vector6s data_imu, data_odom3D;
+    data_imu << 0,0,-wolf::gravity()(2), 0,0,0;
+    data_odom3D << 0,0,0, 0,0,0;
+
+    Scalar input_clock;
+    TimeStamp ts(0);
+    TimeStamp t_odom(0);
+    wolf::CaptureIMUPtr imu_ptr = std::make_shared<CaptureIMU>(ts, sen_imu, data_imu);
+    wolf::CaptureMotionPtr mot_ptr = std::make_shared<CaptureMotion>(t, sen_odom3D, data_odom3D, 6, 6);
+    
+    //read first odom data from file
+    odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+    t_odom.set(input_clock);
+    //when we find a IMU timestamp corresponding with this odometry timestamp then we process odometry measurement
+
+    while( !imu_data_input.eof() && !odom_data_input.eof() )
+    {
+        // PROCESS IMU DATA
+        // Time and data variables
+        imu_data_input >> input_clock >> data_imu[0] >> data_imu[1] >> data_imu[2] >> data_imu[3] >> data_imu[4] >> data_imu[5]; //Ax, Ay, Az, Gx, Gy, Gz
+
+        ts.set(input_clock);
+        imu_ptr->setTimeStamp(ts);
+        imu_ptr->setData(data_imu);
+
+        // process data in capture
+        imu_ptr->getTimeStamp();
+        sen_imu->process(imu_ptr);
+
+        if(ts.get() == t_odom.get()) //every 100 ms
+        {
+            // PROCESS ODOM 3D DATA
+            mot_ptr->setTimeStamp(t_odom);
+            mot_ptr->setData(data_odom3D);
+            sen_odom3D->process(mot_ptr);
+
+            //prepare next odometry measurement if there is any
+            odom_data_input >> input_clock >> data_odom3D[0] >> data_odom3D[1] >> data_odom3D[2] >> data_odom3D[3] >> data_odom3D[4] >> data_odom3D[5];
+            t_odom.set(input_clock);
+        }
+    }
+
+    //closing file
+    imu_data_input.close();
+    odom_data_input.close();
+
+    //===================================================== END{PROCESS DATA}
+
+    //===================================================== SOLVER PART
+
+    //Check and print wolf tree
+    if(wolf_problem_ptr_->check()){
+        wolf_problem_ptr_->print(4,1,1,1);
+    }
+     
+    std::cout << "\t\t\t ______solving______" << std::endl;
+    ceres::Solver::Summary summary = ceres_manager_wolf_diff->solve();
+    std::cout << summary.FullReport() << std::endl;
+    std::cout << "\t\t\t ______solved______" << std::endl;
+    
+    wolf_problem_ptr_->print(4,1,1,1);
+
+    // COMPUTE COVARIANCES
+    std::cout << "\t\t\t ______computing covariances______" << std::endl;
+    ceres_manager_wolf_diff->computeCovariances(ALL);//ALL_MARGINALS, ALL
+    std::cout << "\t\t\t ______computed!______" << std::endl;
+
+    //===================================================== END{SOLVER PART}
+}
+
+int main(int argc, char **argv)
+{
+  ::testing::InitGoogleTest(&argc, argv);
+  ::testing::GTEST_FLAG(filter) = "ProcessorIMU_Odom_tests_details.*:ProcessorIMU_Odom_tests_plateform_simulation.*";
+  //google::InitGoogleLogging(argv[0]);
+  return RUN_ALL_TESTS();
+}
diff --git a/src/test/gtest_processor_imu.cpp b/src/test/gtest_processor_imu.cpp
index d7cc239338c7ba230c5624ef10584eb26a50eb09..c81c2e63088444b40917276da8550de664a02120 100644
--- a/src/test/gtest_processor_imu.cpp
+++ b/src/test/gtest_processor_imu.cpp
@@ -7,54 +7,261 @@
 
 
 
-
-
 #include "utils_gtest.h"
 #include "../src/logging.h"
 
 #include "../sensor_imu.h"
 #include "../processor_imu.h"
 #include "../capture_imu.h"
+#include "rotations.h"
+#include <cmath>
+#include "ceres_wrapper/ceres_manager.h"
+#include "constraint_odom_3D.h"
 
 #include <iostream>
 
-using namespace wolf;
 using namespace Eigen;
-using std::shared_ptr;
-using std::make_shared;
-using std::static_pointer_cast;
-using namespace wolf::Constants;
 
+class ProcessorIMUt : public testing::Test
+{
+
+    public: //These can be accessed in fixtures
+        wolf::ProblemPtr problem;
+        wolf::SensorBasePtr sensor_ptr;
+        wolf::TimeStamp t;
+        wolf::Scalar mti_clock, tmp;
+        Vector6s data;
+        Matrix6s data_cov;
+        VectorXs x0;
+        std::shared_ptr<wolf::CaptureIMU> cap_imu_ptr;
+
+    //a new of this will be created for each new test
+    virtual void SetUp()
+    {
+        using namespace wolf;
+        using namespace Eigen;
+        using std::shared_ptr;
+        using std::make_shared;
+        using std::static_pointer_cast;
+        using namespace wolf::Constants;
+
+        std::string wolf_root = _WOLF_ROOT_DIR;
 
-// Wolf problem
-ProblemPtr problem = Problem::create("PQVBB 3D");
-Vector7s extrinsics = (Vector7s()<<1,0,0, 0,0,0,1).finished();
-SensorBasePtr    sensor_ptr     = problem->installSensor("IMU", "Main IMU", extrinsics, IntrinsicsBasePtr());
-ProcessorBasePtr processor_ptr  = problem->installProcessor("IMU", "IMU pre-integrator", "Main IMU", "");
+        // Wolf problem
+        problem = Problem::create("PQVBB 3D");
+        Vector7s extrinsics = (Vector7s()<<1,0,0, 0,0,0,1).finished();
+        sensor_ptr = problem->installSensor("IMU", "Main IMU", extrinsics,  wolf_root + "/src/examples/sensor_imu.yaml");
+        ProcessorBasePtr processor_ptr = problem->installProcessor("IMU", "IMU pre-integrator", "Main IMU", "");
 
-// Time and data variables
-TimeStamp t;
-Scalar mti_clock, tmp;
-Vector6s data = Vector6s::Zero();
-Matrix6s data_cov = Matrix6s::Identity();
+        // Time and data variables
+        data = Vector6s::Zero();
+        data_cov = Matrix6s::Identity();
+
+        // Set the origin
+        x0.resize(16);
+
+        // Create one capture to store the IMU data arriving from (sensor / callback / file / etc.)
+        cap_imu_ptr = make_shared<CaptureIMU>(t, sensor_ptr, data);
+    }
+
+    virtual void TearDown()
+    {
+        // code here will be called just after the test completes
+        // ok to through exceptions from here if need be
+        /*
+            You can do deallocation of resources in TearDown or the destructor routine. 
+                However, if you want exception handling you must do it only in the TearDown code because throwing an exception 
+                from the destructor results in undefined behavior.
+            The Google assertion macros may throw exceptions in platforms where they are enabled in future releases. 
+                Therefore, it's a good idea to use assertion macros in the TearDown code for better maintenance.
+        */
+    }
+};
+
+
+TEST(ProcessorIMU_constructors, ALL)
+{
+    using namespace wolf;
 
+    //constructor without any argument
+    ProcessorIMUPtr prc0 = std::make_shared<ProcessorIMU>();
+    ASSERT_EQ(prc0->getMaxTimeSpan(), 1.0);
+    ASSERT_EQ(prc0->getMaxBuffLength(), 10000);
+    ASSERT_EQ(prc0->getDistTraveled(), 1.0);
+    ASSERT_EQ(prc0->getAngleTurned(), 0.2);
 
-// Set the origin
-VectorXs x0(16);
+    //constructor with ProcessorIMUParamsPtr argument only
+    ProcessorIMUParamsPtr param_ptr = std::make_shared<ProcessorIMUParams>();
+    param_ptr->max_time_span = 2.0;
+    param_ptr->max_buff_length = 20000;
+    param_ptr->dist_traveled = 2.0;
+    param_ptr->angle_turned = 2.0;
 
-// Create one capture to store the IMU data arriving from (sensor / callback / file / etc.)
-CaptureIMUPtr cap_imu_ptr = make_shared<CaptureIMU>(t, sensor_ptr, data);
+    ProcessorIMUPtr prc1 = std::make_shared<ProcessorIMU>(param_ptr);
+    ASSERT_EQ(prc1->getMaxTimeSpan(), param_ptr->max_time_span);
+    ASSERT_EQ(prc1->getMaxBuffLength(), param_ptr->max_buff_length);
+    ASSERT_EQ(prc1->getDistTraveled(), param_ptr->dist_traveled);
+    ASSERT_EQ(prc1->getAngleTurned(), param_ptr->angle_turned);
 
+    //Factory constructor without yaml
+    std::string wolf_root = _WOLF_ROOT_DIR;
+    ProblemPtr problem = Problem::create("PQVBB 3D");
+    Vector7s extrinsics = (Vector7s()<<1,0,0, 0,0,0,1).finished();
+    SensorBasePtr sensor_ptr = problem->installSensor("IMU", "Main IMU", extrinsics, wolf_root + "/src/examples/sensor_imu.yaml");
+    ProcessorBasePtr processor_ptr = problem->installProcessor("IMU", "IMU pre-integrator", "Main IMU", "");
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxTimeSpan(), 1.0);
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxBuffLength(), 10000);
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getDistTraveled(), 1.0);
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getAngleTurned(), 0.2);
 
+    //Factory constructor with yaml
+    processor_ptr = problem->installProcessor("IMU", "Sec IMU pre-integrator", "Main IMU", wolf_root + "/src/examples/processor_imu.yaml");
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxTimeSpan(), 2.0);
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxBuffLength(), 20000);
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getDistTraveled(), 2.0);
+    ASSERT_EQ(std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getAngleTurned(), 0.2);
+}
 
-TEST(ProcessorIMU, acc_x)
+TEST(ProcessorIMU, voteForKeyFrame)
+{
+    using namespace wolf;
+    using namespace Eigen;
+    using std::shared_ptr;
+    using std::make_shared;
+    using std::static_pointer_cast;
+    using namespace wolf::Constants;
+
+    std::string wolf_root = _WOLF_ROOT_DIR;
+
+    // Wolf problem
+    ProblemPtr problem = Problem::create("PQVBB 3D");
+    Vector7s extrinsics = (Vector7s()<<1,0,0, 0,0,0,1).finished();
+    SensorBasePtr sensor_ptr = problem->installSensor("IMU", "Main IMU", extrinsics,  wolf_root + "/src/examples/sensor_imu.yaml");
+    ProcessorIMUParamsPtr prc_imu_params = std::make_shared<ProcessorIMUParams>();
+    prc_imu_params->max_time_span = 1;
+    prc_imu_params->max_buff_length = 1000000000; //make it very high so that this condition will not pass
+    prc_imu_params->dist_traveled = 1000000000;
+    prc_imu_params->angle_turned = 1000000000;
+    prc_imu_params->voting_active = true;
+    ProcessorBasePtr processor_ptr = problem->installProcessor("IMU", "IMU pre-integrator", sensor_ptr, prc_imu_params);
+    
+    //setting origin
+    VectorXs x0(16);
+    TimeStamp t(0);
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,.000,  0,0,.000; // Try some non-zero biases
+    problem->getProcessorMotionPtr()->setOrigin(x0, t); //this also creates a keyframe at origin
+
+    //data variable and covariance matrix
+    // since we integrate only a few times, give the capture a big covariance, otherwise it will be so small that it won't pass following assertions
+    Vector6s data;
+    data << 1,0,0, 0,0,0;
+    Matrix6s data_cov(Matrix6s::Identity());
+    data_cov(0,0) = 0.5;
+
+    // Create the captureIMU to store the IMU data arriving from (sensor / callback / file / etc.)
+    std::shared_ptr<wolf::CaptureIMU> cap_imu_ptr = make_shared<CaptureIMU>(t, sensor_ptr, data, data_cov);
+
+    //  Time  
+    // we want more than one data to integrate otherwise covariance will be 0
+    Scalar dt = std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxTimeSpan() - 0.1;
+    t.set(dt);
+    cap_imu_ptr->setTimeStamp(t);
+    sensor_ptr->process(cap_imu_ptr);
+
+    dt = std::static_pointer_cast<ProcessorIMU>(processor_ptr)->getMaxTimeSpan() + 0.1;
+    t.set(dt);
+    cap_imu_ptr->setTimeStamp(t);
+    sensor_ptr->process(cap_imu_ptr);
+
+    /*There should be 3 frames :
+        - 1 KeyFrame at origin
+        - 1 keyframe created by process() in voteForKeyFrame() since conditions to create a keyframe are met
+        - 1 frame that would be used by future data
+    */
+    ASSERT_EQ(problem->getTrajectoryPtr()->getFrameList().size(),3);
+
+    /* if max_time_span == 2,  Wolf tree should be
+
+    Hardware
+        S1
+            pm5
+            o: C2 - F2
+            l: C4 - F3
+        Trajectory
+        KF1
+            Estim, ts=0,	 x = ( 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0)
+            C1 -> S1
+        KF2
+            Estim, ts=2.1,	 x = ( 2.2     0       -22     0       0       0       1       2.1     0       -21     0       0       0       0       0       0      )
+            C2 -> S1
+                f1
+                    m = ( 2.21 0   0   0   0   0   1   2.1 0   0  )
+                    c1 --> F1
+        F3
+            Estim, ts=2.1,	 x = ( . . .)
+            C4 -> S1
+    */
+    //TODO : ASSERT TESTS to make sure the constraints are correctly set + check the tree above
+
+}
+
+//replace TEST by TEST_F if SetUp() needed
+TEST_F(ProcessorIMUt, interpolate)
+{
+    using namespace wolf;
+
+    t.set(0);
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    data << 2, 0, 0, 0, 0, 0; // only acc_x
+    cap_imu_ptr->setData(data);
+
+    // make one step to depart from origin
+    cap_imu_ptr->setTimeStamp(0.05);
+    sensor_ptr->process(cap_imu_ptr);
+    Motion mot_ref = problem->getProcessorMotionPtr()->getMotion();
+
+    // make two steps, then pretend it's just one
+    cap_imu_ptr->setTimeStamp(0.10);
+    sensor_ptr->process(cap_imu_ptr);
+    Motion mot_int_gt = problem->getProcessorMotionPtr()->getMotion();
+
+    cap_imu_ptr->setTimeStamp(0.15);
+    sensor_ptr->process(cap_imu_ptr);
+    Motion mot_final = problem->getProcessorMotionPtr()->getMotion();
+    mot_final.delta_ = mot_final.delta_integr_;
+    Motion mot_sec = mot_final;
+
+    problem->getProcessorMotionPtr()->getBuffer().print(0,1,1,0);
+
+class P : wolf::ProcessorIMU
+{
+    public:
+        Motion interp(const Motion& ref, Motion& sec, TimeStamp ts)
+        {
+            return ProcessorIMU::interpolate(ref, sec, ts);
+        }
+} imu;
+
+Motion mot_int = imu.interp(mot_ref, mot_sec, TimeStamp(0.10));
+
+ASSERT_MATRIX_APPROX(mot_int.data_,  mot_int_gt.data_, 1e-6);
+//ASSERT_MATRIX_APPROX(mot_int.delta_, mot_int_gt.delta_, 1e-6); // FIXME: delta_p not correctly interpolated
+ASSERT_MATRIX_APPROX(mot_final.delta_integr_,  mot_sec.delta_integr_, 1e-6);
+
+
+}
+
+TEST_F(ProcessorIMUt, acc_x)
 {
     t.set(0); // clock in 0,1 ms ticks
     x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
 
     problem->getProcessorMotionPtr()->setOrigin(x0, t);
 
-    data << 2, 0, 9.8, 0, 0, 0; // only acc_x, but measure gravity!
+    data << 2, 0, 9.806, 0, 0, 0; // only acc_x, but measure gravity!
 
     cap_imu_ptr->setData(data);
     cap_imu_ptr->setTimeStamp(0.1);
@@ -64,17 +271,52 @@ TEST(ProcessorIMU, acc_x)
     VectorXs x(16);
     x << 0.01,0,0, 0,0,0,1, 0.2,0,0, 0,0,0, 0,0,0; // advanced at a=2m/s2 during 0.1s ==> dx = 0.5*2*0.1^2 = 0.01; dvx = 2*0.1 = 0.2
 
-    ASSERT_TRUE((problem->getCurrentState() - x).isMuchSmallerThan(1, EPS_SMALL));
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
 }
 
-TEST(ProcessorIMU, acc_z)
+TEST_F(ProcessorIMUt, acc_y)
 {
+    // last part of this test fails with precision wolf::Constants::EPS_SMALL beacause error is in 1e-12
+    // difference hier is that we integrate over 1ms periods
+
     t.set(0); // clock in 0,1 ms ticks
     x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
 
     problem->getProcessorMotionPtr()->setOrigin(x0, t);
 
-    data << 0, 0, 9.8 + 2.0, 0, 0, 0; // only acc_z, but measure gravity!
+    data << 0, 20, 9.806, 0, 0, 0; // only acc_y, but measure gravity!
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    VectorXs x(16);
+    x << 0,0.00001,0, 0,0,0,1, 0,0.02,0, 0,0,0, 0,0,0; // advanced at a=20m/s2 during 0.001s ==> dx = 0.5*20*0.001^2 = 0.00001; dvx = 20*0.001 = 0.02
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 5s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        cap_imu_ptr->setTimeStamp(i*0.001 + 0.001); //first one will be 0.002 and last will be 5.000
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    // advanced at a=20m/s2 during 1s ==> dx = 0.5*20*1^2 = 10; dvx = 20*1 = 20
+    x << 0,10,0, 0,0,0,1, 0,20,0, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS);// << "current state is " << problem->getCurrentState().transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, acc_z)
+{
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    data << 0, 0, 9.806 + 2.0, 0, 0, 0; // only acc_z, but measure gravity!
 
     cap_imu_ptr->setData(data);
     cap_imu_ptr->setTimeStamp(0.1);
@@ -84,10 +326,140 @@ TEST(ProcessorIMU, acc_z)
     VectorXs x(16);
     x << 0,0,0.01, 0,0,0,1, 0,0,0.2, 0,0,0, 0,0,0; // advanced at a=2m/s2 during 0.1s ==> dz = 0.5*2*0.1^2 = 0.01; dvz = 2*0.1 = 0.2
 
-    ASSERT_TRUE((problem->getCurrentState() - x).isMuchSmallerThan(1, EPS_SMALL));
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 5s
+    const unsigned int iter = 50; //how 0.1s 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        cap_imu_ptr->setTimeStamp(i*0.1 + 0.1); //first one will be 0.2 and last will be 5.0
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    // advanced at a=2m/s2 during 5s ==> dz = 0.5*2*5^2 = 25; dvz = 2*5 = 10
+    x << 0,0,25, 0,0,0,1, 0,0,10, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS);// << "current state is " << problem->getCurrentState().transpose() << "\n x is : " << x.transpose() << std::endl;
 }
 
-TEST(ProcessorIMU, Covariances)
+TEST_F(ProcessorIMUt, acc_xyz)
+{
+    /* Here again the error seems to be in the discretization.
+     * integrating over 10s with a dt of 0.001s lead to an error in velocity of order 1e-3. 
+     * The smaller is the time step the more precise is the integration
+     * Same conclusion for position
+     */
+
+    Vector3s tmp_a_vec; //will be used to store IMU acceleration data
+    Vector3s w_vec((Vector3s()<<0,0,0).finished());
+    wolf::Scalar time = 0;
+    const wolf::Scalar x_freq = 2;
+    const wolf::Scalar y_freq = 1;
+    const wolf::Scalar z_freq = 4;
+
+    wolf::Scalar tmp_ax, tmp_ay, tmp_az;
+    /*
+        From evolution of position we determine the acceleration : 
+        x = sin(x_freq*t);
+        y = sin(y_freq*t);
+        z = sin(z_freq*t);
+
+        corresponding acceleration
+        ax = - (x_freq * x_freq) * sin(x_freq * t);
+        ay = - (y_freq * y_freq) * sin(y_freq * t);
+        az = - (z_freq * z_freq) * sin(z_freq * t);
+
+        Notice that in this case, initial velocity is given exactly as :
+        initial_vx = x_freq;
+        initial_vy = y_freq;
+        initial_vz = z_freq;
+     */
+
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  x_freq,y_freq,z_freq,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    const wolf::Scalar dt = 0.0001;
+    
+    // This test is for pure translation -> no rotation ==> constant rate of turn vector = [0,0,0]
+    data.tail(3) = w_vec;
+
+    for(unsigned int data_iter = 0; data_iter <= 1000; data_iter ++)
+    {   
+        tmp_ax = - (x_freq * x_freq) * sin(x_freq * time);
+        tmp_ay = - (y_freq * y_freq) * sin(y_freq * time);
+        tmp_az = - (z_freq * z_freq) * sin(z_freq * time);
+        tmp_a_vec << tmp_ax, tmp_ay, tmp_az;
+
+        Quaternions rot(problem->getCurrentState().data()+3); //should always be identity quaternion here...
+        data.head(3) =  tmp_a_vec + rot.conjugate() * (- wolf::gravity()); //gravity measured
+
+        cap_imu_ptr->setData(data);
+        cap_imu_ptr->setTimeStamp(time);
+        sensor_ptr->process(cap_imu_ptr);
+
+        time += dt;
+    }
+    time -= dt; //to get final time
+
+    /* We should not have turned : final quaternion must be identity quaternion [0,0,0,1]
+     * We integrated over 1 s : 
+     * x = sin(x_freq * 1)
+     * y = sin(y_freq * 1)
+     * z = sin(z_freq * 1)
+
+     * Velocity is given by first derivative :
+     * vx = x_freq * cos(x_freq * 1)
+     * vy = y_freq * cos(y_freq * 1)
+     * vz = z_freq * cos(z_freq * 1)
+     */
+
+    VectorXs x(16);
+    wolf::Scalar exp_px = sin(x_freq * time);
+    wolf::Scalar exp_py = sin(y_freq * time);
+    wolf::Scalar exp_pz = sin(z_freq * time);
+
+    wolf::Scalar exp_vx = x_freq * cos(x_freq * time);
+    wolf::Scalar exp_vy = y_freq * cos(y_freq * time);
+    wolf::Scalar exp_vz = z_freq * cos(z_freq * time);
+
+    x << exp_px,exp_py,exp_pz, 0,0,0,1, exp_vx,exp_vy,exp_vz, 0,0,0, 0,0,0;
+
+    //check velocity and bias parts
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().tail(9) , x.tail(9), 0.001);// << "current VBB is : \n" << problem->getCurrentState().tail(9).transpose() <<
+//    "\n expected is : \n" << x.tail(9).transpose() << std::endl;
+
+    //check orientation part
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().segment(3,4) , x.segment(3,4), wolf::Constants::EPS_SMALL*10);// << "current orientation is : \n" << problem->getCurrentState().segment(3,4).transpose() <<
+//    "\n expected is : \n" << x.segment(3,4).transpose() << std::endl;
+
+    //check position part
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().head(3) , x.head(3), 0.001);// << "current position is : \n" << problem->getCurrentState().head(3).transpose() <<
+//    "\n expected is : \n" << x.head(3).transpose() << std::endl;
+
+}
+
+TEST_F(ProcessorIMUt, check_Covariance)
+{
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    data << 2, 0, 9.806, 0, 0, 0; // only acc_x, but measure gravity!
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.1);
+    sensor_ptr->process(cap_imu_ptr);
+
+    VectorXs delta_preint(problem->getProcessorMotionPtr()->getMotion().delta_integr_);
+//    Matrix<wolf::Scalar,9,9> delta_preint_cov = problem->getProcessorMotionPtr()->getCurrentDeltaPreintCov();
+
+    ASSERT_FALSE(delta_preint.isMuchSmallerThan(1, wolf::Constants::EPS_SMALL));
+//    ASSERT_MATRIX_APPROX(delta_preint_cov, MatrixXs::Zero(9,9), wolf::Constants::EPS_SMALL); // << "delta_preint_cov :\n" << delta_preint_cov; //covariances computed only at keyframe creation
+}
+
+TEST_F(ProcessorIMUt, Covariances)
 {
     data_cov.topLeftCorner(3,3)     *= 0.01; // acc variance
     data_cov.bottomRightCorner(3,3) *= 0.01; // gyro variance
@@ -95,10 +467,698 @@ TEST(ProcessorIMU, Covariances)
 
 }
 
+TEST_F(ProcessorIMUt, gyro_x)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 0, 9.806, rate_of_turn, 0, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, 0,0,0, 0,0,0; // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 5s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity());
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS);// << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_x_biasedAbx)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    wolf::Scalar abx(0.002);
+    Vector3s acc_bias((Vector3s()<<abx,0,0).finished());
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  abx,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0+abx, 0, 9.806, rate_of_turn, 0, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, abx,0,0, 0,0,0; // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);// << "expected state : " << problem->getCurrentState().transpose()
+//    << "\n estimated state : " << x.transpose();
+
+    //do so for 5s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()) + acc_bias;
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, abx,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS);// << "estimated state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n expected state is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_xy_biasedAbxy)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    wolf::Scalar abx(0.002), aby(0.01);
+    Vector3s acc_bias((Vector3s()<<abx,aby,0).finished());
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  abx,aby,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0+abx, 0+aby, 9.806, rate_of_turn, rate_of_turn*1.5, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, abx,aby,0, 0,0,0;
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);// << "expected state : " << problem->getCurrentState().transpose()
+//    << "\n estimated state : " << x.transpose();
+
+    //do so for 5s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()) + acc_bias;
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, abx,aby,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS);// << "estimated state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n expected state is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_z)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0;
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 0, 9.806, 0, 0, rate_of_turn; // measure gravity!
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, 0,0,0, 0,0,0; // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 5s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 0,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS);// << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_xyz)
+{
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    Vector3s tmp_vec; //will be used to store rate of turn data
+    Quaternions quat_comp(Quaternions::Identity());
+    Matrix3s R0(Matrix3s::Identity());
+    wolf::Scalar time = 0;
+    const unsigned int x_rot_vel = 5;
+    const unsigned int y_rot_vel = 6;
+    const unsigned int z_rot_vel = 13;
+
+    wolf::Scalar tmpx, tmpy, tmpz;
+    
+    /*
+        ox oy oz evolution in degrees (for understanding) --> converted in rad
+        with * pi/180
+        ox = pi*sin(alpha*t*pi/180); %express angle in rad before using sinus
+        oy = pi*sin(beta*t*pi/180);
+        oz = pi*sin(gamma*t*pi/180);
+
+        corresponding rate of turn
+        %rate of turn expressed in radians/s
+        wx = pi*alpha*cos(alpha*t*pi/180)*pi/180;
+        wy = pi*beta*cos(beta*t*pi/180)*pi/180;
+        wz = pi*gamma*cos(gamma*t*pi/180)*pi/180;
+     */
+
+     const wolf::Scalar dt = 0.001;
+
+    for(unsigned int data_iter = 0; data_iter <= 1000; data_iter ++)
+    {   
+        time += dt;
+
+        tmpx = M_PI*x_rot_vel*cos((M_PI/180) * x_rot_vel * time)*M_PI/180;
+        tmpy = M_PI*y_rot_vel*cos((M_PI/180) * y_rot_vel * time)*M_PI/180;
+        tmpz = M_PI*z_rot_vel*cos((M_PI/180) * z_rot_vel * time)*M_PI/180;
+        tmp_vec << tmpx, tmpy, tmpz;
+
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(tmp_vec*dt);
+        R0 = R0 * wolf::v2R(tmp_vec*dt);
+        // use processorIMU
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()); //gravity measured
+        data.tail(3) = tmp_vec;
+
+        cap_imu_ptr->setData(data);
+        cap_imu_ptr->setTimeStamp(time);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    /* We focus on orientation here. position is supposed not to have moved
+     * we integrated using 2 ways : 
+        - a direct quaternion composition q = q (x) q(w*dt)
+        - using methods implemented in processorIMU
+
+        We check one against the other
+     */
+
+     // validating that the quaternion composition and rotation matrix composition actually describe the same rotation.
+    Quaternions R2quat(wolf::v2q(wolf::R2v(R0)));
+    Vector4s quat_comp_vec((Vector4s() <<quat_comp.x(), quat_comp.y(), quat_comp.z(), quat_comp.w()).finished() );
+    Vector4s R2quat_vec((Vector4s() <<R2quat.x(), R2quat.y(), R2quat.z(), R2quat.w()).finished() );
+
+    ASSERT_MATRIX_APPROX(quat_comp_vec , R2quat_vec, wolf::Constants::EPS);// << "quat_comp_vec : " << quat_comp_vec.transpose() << "\n R2quat_vec : " << R2quat_vec.transpose() << std::endl;
+
+    VectorXs x(16);
+    x << 0,0,0, quat_comp.x(), quat_comp.y(), quat_comp.z(), quat_comp.w(), 0,0,0, 0,0,0, 0,0,0;
+
+    Quaternions result_quat(problem->getCurrentState().data() + 3);
+    //std::cout << "final orientation : " << wolf::q2v(result_quat).transpose() << std::endl;
+
+    //check position part
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().head(3) , x.head(3), wolf::Constants::EPS);// << "current position is : \n" << problem->getCurrentState().head(3).transpose() <<
+//    "\n expected is : \n" << x.head(3).transpose() << std::endl;
+
+    //check velocity and bias parts
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().tail(9) , x.tail(9), wolf::Constants::EPS);// << "current VBB is : \n" << problem->getCurrentState().tail(9).transpose() <<
+//    "\n expected is : \n" << x.tail(9).transpose() << std::endl;
+
+    //check orientation part
+    EXPECT_MATRIX_APPROX(problem->getCurrentState().segment(3,4) , x.segment(3,4) , wolf::Constants::EPS);// << "current orientation is : \n" << problem->getCurrentState().segment(3,4).transpose() <<
+//    "\n expected is : \n" << x.segment(3,4).transpose() << std::endl;
+    // expect above fails, look for the actual precision that works
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().segment(3,4) , x.segment(3,4) , 0.001);// << "current orientation is : \n" << problem->getCurrentState().segment(3,4).transpose() <<
+//    "\n expected is : \n" << x.segment(3,4).transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_z_ConstVelocity)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  2,0,0,  0,0,0,  0,0,0;
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << -wolf::gravity(), 0, 0, rate_of_turn; // measure gravity!
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    x << 0.002,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0; // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180, 2m/s * 0.001s = 0.002m
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 5.000
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 2,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0; //2m/s * 1s = 2m
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_x_ConstVelocity)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  2,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 0, 9.806, rate_of_turn, 0, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180, 2m/s * 0.001s = 0.002
+    x << 0.002,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0;
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity());
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 2,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0; //2m/s * 1s = 2m
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_xy_ConstVelocity)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  2,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 0, 9.806, 0, rate_of_turn, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180, 2m/s * 0.001s = 0.002
+    x << 0.002,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0;
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity());
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 2,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0; //2m/s * 1s = 2m
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_y_ConstVelocity)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  2,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 0, 9.806, 0, rate_of_turn, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180, 2m/s * 0.001s = 0.002
+    x << 0.002,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0;
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS_SMALL);
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 1; i < iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity());
+
+        cap_imu_ptr->setTimeStamp(i*dt + dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    x << 2,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 2,0,0, 0,0,0, 0,0,0; //2m/s * 1s = 2m
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_xyz_ConstVelocity)
+{
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  2,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    Vector3s tmp_vec; //will be used to store rate of turn data
+    Quaternions quat_comp(Quaternions::Identity());
+    Matrix3s R0(Matrix3s::Identity());
+    wolf::Scalar time = 0;
+    const unsigned int x_rot_vel = 5;
+    const unsigned int y_rot_vel = 6;
+    const unsigned int z_rot_vel = 13;
+
+    wolf::Scalar tmpx, tmpy, tmpz;
+    
+    /*
+        ox oy oz evolution in degrees (for understanding) --> converted in rad
+        with * pi/180
+        ox = pi*sin(alpha*t*pi/180); %express angle in rad before using sinus
+        oy = pi*sin(beta*t*pi/180);
+        oz = pi*sin(gamma*t*pi/180);
+
+        corresponding rate of turn
+        %rate of turn expressed in radians/s
+        wx = pi*alpha*cos(alpha*t*pi/180)*pi/180;
+        wy = pi*beta*cos(beta*t*pi/180)*pi/180;
+        wz = pi*gamma*cos(gamma*t*pi/180)*pi/180;
+     */
+
+     const wolf::Scalar dt = 0.001;
+
+    for(unsigned int data_iter = 0; data_iter < 1000; data_iter ++)
+    {   
+        time += dt;
+
+        tmpx = M_PI*x_rot_vel*cos((M_PI/180) * x_rot_vel * time)*M_PI/180;
+        tmpy = M_PI*y_rot_vel*cos((M_PI/180) * y_rot_vel * time)*M_PI/180;
+        tmpz = M_PI*z_rot_vel*cos((M_PI/180) * z_rot_vel * time)*M_PI/180;
+        tmp_vec << tmpx, tmpy, tmpz;
+
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(tmp_vec*dt);
+        R0 = R0 * wolf::v2R(tmp_vec*dt);
+        // use processorIMU
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()); //gravity measured
+        data.tail(3) = tmp_vec;
+
+        cap_imu_ptr->setData(data);
+        cap_imu_ptr->setTimeStamp(time);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    /* We focus on orientation here. position is supposed not to have moved
+     * we integrated using 2 ways : 
+        - a direct quaternion composition q = q (x) q(w*dt)
+        - using methods implemented in processorIMU
+
+        We check one against the other
+     */
+
+     // validating that the quaternion composition and rotation matrix composition actually describe the same rotation.
+    Quaternions R2quat(wolf::v2q(wolf::R2v(R0)));
+    Vector4s quat_comp_vec((Vector4s() <<quat_comp.x(), quat_comp.y(), quat_comp.z(), quat_comp.w()).finished() );
+    Vector4s R2quat_vec((Vector4s() <<R2quat.x(), R2quat.y(), R2quat.z(), R2quat.w()).finished() );
+
+    ASSERT_MATRIX_APPROX(quat_comp_vec , R2quat_vec, wolf::Constants::EPS); // << "quat_comp_vec : " << quat_comp_vec.transpose() << "\n R2quat_vec : " << R2quat_vec.transpose() << std::endl;
+
+    VectorXs x(16);
+    //rotation + translation due to initial velocity
+    x << 2,0,0, quat_comp.x(), quat_comp.y(), quat_comp.z(), quat_comp.w(), 2,0,0, 0,0,0, 0,0,0;
+
+    Quaternions result_quat(problem->getCurrentState().data() + 3);
+    //std::cout << "final orientation : " << wolf::q2v(result_quat).transpose() << std::endl;
+
+    //check position part
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().head(3) , x.head(3), wolf::Constants::EPS); // << "current position is : \n" << problem->getCurrentState().head(3).transpose() <<
+//    "\n expected is : \n" << x.head(3).transpose() << std::endl;
+
+    //check velocity and bias parts
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().tail(9) , x.tail(9), wolf::Constants::EPS); // << "current VBB is : \n" << problem->getCurrentState().tail(9).transpose() <<
+//    "\n expected is : \n" << x.tail(9).transpose() << std::endl;
+
+    //check orientation part
+    EXPECT_MATRIX_APPROX(problem->getCurrentState().segment(3,4) , x.segment(3,4) , wolf::Constants::EPS); // << "current orientation is : \n" << problem->getCurrentState().segment(3,4).transpose() <<
+//    "\n expected is : \n" << x.segment(3,4).transpose() << std::endl;
+    // expect above fails, look for the actual precision that works
+    ASSERT_MATRIX_APPROX(problem->getCurrentState().segment(3,4) , x.segment(3,4) , 0.001); // << "current orientation is : \n" << problem->getCurrentState().segment(3,4).transpose() <<
+//    "\n expected is : \n" << x.segment(3,4).transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_x_acc_x)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 1, 0, -wolf::gravity()(2), rate_of_turn, 0, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180 on x axis
+    // translation with constant acc : 1 m/s^2 for 0.001 second. Initial velocity : 0, p = 0.5*a*dt^2 + v*dt = 0.5*1*0.001^2 = 0.0000005 on x axis
+    // v = a*dt = 0.001
+    x << 0.0000005,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0.001,0,0, 0,0,0, 0,0,0; 
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "1. current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 2; i <= iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()) + (Vector3s()<<1,0,0).finished();
+
+        cap_imu_ptr->setTimeStamp(i*dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    // translation with constant acc : 1 m/s for 1 second. Initial velocity : 0, p = 0.5*a*dt + v*dt = 0.5 on x axis
+    // v = a*dt = 1
+    x << 0.5,0,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 1,0,0, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_y_acc_y)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 1, -wolf::gravity()(2), 0, rate_of_turn, 0; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180 on y axis
+    // translation with constant acc : 1 m/s^2 for 0.001 second. Initial velocity : 0, p = 0.5*a*dt^2 + v*dt = 0.5*1*0.001^2 = 0.0000005 on y axis
+    // v = a*dt = 0.001
+    x << 0,0.0000005,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0.001,0, 0,0,0, 0,0,0; 
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "1. current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 2; i <= iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()) + (Vector3s()<<0,1,0).finished();
+
+        cap_imu_ptr->setTimeStamp(i*dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    // translation with constant acc : 1 m/s for 1 second. Initial velocity : 0, p = 0.5*a*dt + v*dt = 0.5 on y axis
+    // v = a*dt = 1
+    x << 0,0.5,0, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,1,0, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
+
+TEST_F(ProcessorIMUt, gyro_z_acc_z)
+{
+    wolf::Scalar dt(0.001);
+    t.set(0); // clock in 0,1 ms ticks
+    x0 << 0,0,0,  0,0,0,1,  0,0,0,  0,0,0,  0,0,0; // Try some non-zero biases
+
+    problem->getProcessorMotionPtr()->setOrigin(x0, t);
+
+    wolf::Scalar rate_of_turn = 5 * M_PI/180.0;
+    data << 0, 0, -wolf::gravity()(2) + 1, 0, 0, rate_of_turn; // measure gravity
+
+    cap_imu_ptr->setData(data);
+    cap_imu_ptr->setTimeStamp(0.001);
+    sensor_ptr->process(cap_imu_ptr);
+
+    // Expected state after one integration
+    Quaternions quat_comp(Quaternions::Identity());
+    quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+    VectorXs x(16);
+    // rotated at 5 deg/s for 0.001s = 0.005 deg => 0.005 * M_PI/180 on z axis
+    // translation with constant acc : 1 m/s^2 for 0.001 second. Initial velocity : 0, p = 0.5*a*dt^2 + v*dt = 0.5*1*0.001^2 = 0.0000005 on z axis
+    // v = a*dt = 0.001
+    x << 0,0,0.0000005, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,0.001, 0,0,0, 0,0,0; 
+
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "1. current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+
+    //do so for 1s
+    const unsigned int iter = 1000; //how many ms 
+    for(int i = 2; i <= iter; i++) //already did one integration above
+    {
+        // quaternion composition
+        quat_comp = quat_comp * wolf::v2q(data.tail(3)*dt);
+
+        Quaternions rot(problem->getCurrentState().data()+3);
+        data.head(3) =  rot.conjugate() * (- wolf::gravity()) + (Vector3s()<<0,0,1).finished();
+
+        cap_imu_ptr->setTimeStamp(i*dt); //first one will be 0.002 and last will be 1.000
+        cap_imu_ptr->setData(data);
+        sensor_ptr->process(cap_imu_ptr);
+    }
+
+    // translation with constant acc : 1 m/s for 1 second. Initial velocity : 0, p = 0.5*a*dt + v*dt = 0.5 on z axis
+    // v = a*dt = 1
+    x << 0,0,0.5, quat_comp.x(),quat_comp.y(),quat_comp.z(),quat_comp.w(), 0,0,1, 0,0,0, 0,0,0;
+    ASSERT_MATRIX_APPROX(problem->getCurrentState() , x, wolf::Constants::EPS); // << "current state is : \n" << problem->getCurrentState().transpose() <<
+//    "\n current x is : \n" << x.transpose() << std::endl;
+}
 
 int main(int argc, char **argv)
 {
   testing::InitGoogleTest(&argc, argv);
+  //::testing::GTEST_FLAG(filter) = "ProcessorIMUt.check_Covariance";
   return RUN_ALL_TESTS();
 }
 
diff --git a/src/test/gtest_rotation.cpp b/src/test/gtest_rotation.cpp
index ca382f888f1f536cf685009c2648b746f02004f6..4073184084ca4b379a3c61898ac74981c1546fc9 100644
--- a/src/test/gtest_rotation.cpp
+++ b/src/test/gtest_rotation.cpp
@@ -1,5 +1,5 @@
 /**
- * \file test_rotation.cpp
+ * \file gtest_rotation.cpp
  *
  *  Created on: Oct 13, 2016
  *      \author: AtDinesh
@@ -27,6 +27,141 @@
 using namespace wolf;
 using namespace Eigen;
 
+namespace wolf
+{
+
+inline Eigen::VectorXs q2v_aa(const Eigen::Quaternions& _q)
+{
+    Eigen::AngleAxiss aa = Eigen::AngleAxiss(_q);
+    return aa.axis() * aa.angle();
+}
+
+// 'New' version (alternative version also used by ceres)
+template<typename Derived>
+inline Eigen::Quaternion<typename Derived::Scalar> v2q_new(const Eigen::MatrixBase<Derived>& _v)
+{
+    MatrixSizeCheck<3, 1>::check(_v);
+    typedef typename Derived::Scalar T;
+
+    Eigen::Quaternion<T> q;
+    const T& a0 = _v[0];
+    const T& a1 = _v[1];
+    const T& a2 = _v[2];
+    const T angle_square = a0 * a0 + a1 * a1 + a2 * a2;
+
+    //We need the angle : means we have to take the square root of angle_square, 
+    // which is defined for all angle_square beonging to R+ (except 0)
+    if (angle_square > (T)0.0 ){
+        //sqrt is defined here
+        const T angle = sqrt(angle_square);
+        const T angle_half = angle / (T)2.0;
+        
+        q.w() = cos(angle_half);
+        q.vec() = _v / angle * sin(angle_half);
+        return q;
+    }
+    else
+    {
+        //sqrt not defined at 0 and will produce NaNs, thuswe use an approximation with taylor series truncated at one term
+        q.w() = (T)1.0;
+        q.vec() = _v *(T)0.5; // see the Taylor series of sinc(x) ~ 1 - x^2/3!, and have q.vec = v/2 * sinc(angle_half)
+                                                                    //                                 for angle_half == 0 then ,     = v/2
+        return q;
+    }
+}
+
+// 'New' version (alternative version also used by ceres)
+template<typename Derived>
+inline Eigen::Matrix<typename Derived::Scalar, 3, 1> q2v_new(const Eigen::QuaternionBase<Derived>& _q)
+{
+    typedef typename Derived::Scalar T;
+    Eigen::Matrix<T, 3, 1> vec = _q.vec();
+    const T sin_angle_square = vec(0) * vec(0) + vec(1) * vec(1) + vec(2) * vec(2);
+
+    //everything shouold be OK for non-zero rotations
+    if (sin_angle_square > (T)0.0)
+    {
+        const T sin_angle = sqrt(sin_angle_square);
+        const T& cos_angle = _q.w();
+
+        /* If (cos_theta < 0) then theta >= pi/2 , means : angle for angle_axis vector >= pi (== 2*theta) 
+                    |-> results in correct rotation but not a normalized angle_axis vector 
+    
+        In that case we observe that 2 * theta ~ 2 * theta - 2 * pi,
+        which is equivalent saying
+    
+            theta - pi = atan(sin(theta - pi), cos(theta - pi))
+                        = atan(-sin(theta), -cos(theta))
+        */
+        const T two_angle = T(2.0) * ((cos_angle < 0.0) ? atan2(-sin_angle, -cos_angle) : atan2(sin_angle, cos_angle));
+        const T k = two_angle / sin_angle;
+        return vec * k;
+    }
+    else
+    { // small-angle approximation using truncated Taylor series
+        //zero rotation --> sqrt will result in NaN
+        return vec * (T)2.0; // log = 2 * vec * ( 1 - norm(vec)^2 / 3*w^2 ) / w.
+    }
+}
+    
+}
+
+TEST(rotations, v2q_VS_v2q_new) //this test will use functions defined above
+{
+    using namespace wolf;
+    //defines scalars
+    wolf::Scalar deg_to_rad = M_PI/180.0;
+
+    Eigen::Vector4s vec0, vec1;
+
+        //v2q
+    Eigen::Vector3s rot_vector0, rot_vector1;
+    Eigen::Quaternions quat_o, quat_o1, quat_new, quat_new1;
+    Eigen::Vector4s vec_o, vec_o1, vec_new, vec_new1;
+    Eigen::Vector3s qvec_o, qvec_o1, qvec_new, qvec_new1, qvec_aao, qvec_aa1;
+    for (unsigned int iter = 0; iter < 10000; iter ++)
+    {
+        rot_vector0 = Eigen::Vector3s::Random();
+        rot_vector1 = rot_vector0 * 100 *deg_to_rad; //far from origin
+        rot_vector0 = rot_vector0 *0.0001*deg_to_rad; //close to origin
+
+        quat_o = v2q(rot_vector0);
+        quat_new = v2q_new(rot_vector0);
+        quat_o1 = v2q(rot_vector1);
+        quat_new1 = v2q_new(rot_vector1);
+
+        //now we do the checking
+        vec_o << quat_o.w(), quat_o.x(), quat_o.y(), quat_o.z();
+        vec_new << quat_new.w(), quat_new.x(), quat_new.y(), quat_new.z();
+        vec_o1 << quat_o1.w(), quat_o1.x(), quat_o1.y(), quat_o1.z();
+        vec_new1 << quat_new1.w(), quat_new1.x(), quat_new1.y(), quat_new1.z();
+
+        ASSERT_TRUE((vec_o - vec_new).isMuchSmallerThan(1,wolf::Constants::EPS));
+        ASSERT_TRUE((vec_o1 - vec_new1).isMuchSmallerThan(1,wolf::Constants::EPS));
+    
+
+        //q2v
+        qvec_o     = q2v(quat_o);
+        qvec_o1    = q2v(quat_o1);
+        qvec_aao   = q2v_aa(quat_o);
+        qvec_aa1   = q2v_aa(quat_o1);
+        qvec_new   = q2v_new(quat_new);
+        qvec_new1  = q2v_new(quat_new1);
+
+        // 'New' version (alternative version also used by ceres) of q2v is working, result with template version gives the same that the regular version with Eigen::Quaternions argument
+        ASSERT_TRUE((qvec_aao - qvec_new).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_aao : " << qvec_aao.transpose() << "\n qvec_new : " << qvec_new.transpose() << std::endl;
+        ASSERT_TRUE((qvec_aa1 - qvec_new1).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_aa1 : " << qvec_aa1.transpose() << "\n qvec_new1 : " << qvec_new1.transpose() << std::endl;
+        EXPECT_TRUE((qvec_new - rot_vector0).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_new : " << qvec_new.transpose() << "\n rot_vector0 : " << rot_vector0.transpose() << std::endl;
+        EXPECT_TRUE((qvec_new1 - rot_vector1).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_new1 : " << qvec_new1.transpose() << "\n rot_vector1 : " << rot_vector1.transpose() << std::endl;
+
+        // checking current q2v
+        ASSERT_TRUE((qvec_aao - qvec_o).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_aao : " << qvec_aao.transpose() << "\n qvec_new : " << qvec_new.transpose() << std::endl;
+        ASSERT_TRUE((qvec_aa1 - qvec_o1).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_aa1 : " << qvec_aa1.transpose() << "\n qvec_new1 : " << qvec_new1.transpose() << std::endl;
+        EXPECT_TRUE((qvec_o - rot_vector0).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_new : " << qvec_new.transpose() << "\n rot_vector0 : " << rot_vector0.transpose() << std::endl;
+        EXPECT_TRUE((qvec_o1 - rot_vector1).isMuchSmallerThan(1,wolf::Constants::EPS)) << "\n qvec_new1 : " << qvec_new1.transpose() << "\n rot_vector1 : " << rot_vector1.transpose() << std::endl;
+    }
+}
+
 TEST(rotations, pi2pi)
 {
     ASSERT_NEAR(M_PI_2, pi2pi((Scalar)M_PI_2), 1e-10);
@@ -256,163 +391,144 @@ TEST(rotations, Quat_compos_const_rateOfTurn)
 {
     using namespace wolf;
 
-    // ********* constant rate of turn *********
+                                // ********* constant rate of turn *********
+
+    /* First idea was to integrate data on SO3 (succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)) and in R3
+    (q2v(v2q(v0*n*dt))). with v0 << 30.0*deg_to_rad, 5.0*deg_to_rad, 10.0*deg_to_rad : constant rate-of-turn in rad/s and dt the time step.
+    But this is not OK, we cannot expect those 2 rotation integration to be equal.
+    The whole point of the SO3 thing is that we cannot integrate rotation in the R3 space and expect it to work. This is why we must integrate it in the manifold of SO3
+    
+    more specifically : 
+    - At a constant velocity, because we keep a constant rotation axis, the integral is the same.
+    - for non-contant velocities, especially if we change the axis of rotation, then it’s not the same, and the only good method is the SO3.
+
+    We change the idea :
+    define orientation and derive ox, oy, oz so that we get the rate of turn wx, wy, wz.
+    Then compare the final orientation from rotation matrix composition and quaternion composition
+    */
+
     wolf::Scalar deg_to_rad = M_PI/180.0;
-    Quaternions q0;
+    Eigen::Matrix3s rot0(Eigen::Matrix3s::Identity());
+    Eigen::Quaternions q0, qRot;
     q0.setIdentity();
-    Vector3s v0, v1, v2;
-    VectorXs const_diff_ox, const_diff_oy, const_diff_oz, ox, oy, oz, qox, qoy, qoz;
-    VectorXs cdox_abs, cdoy_abs, cdoz_abs, vector0, t_vec; //= const_diff_## with absolute values
-    const wolf::Scalar dt = 0.001;
-    const wolf::Scalar N = 100;
-
-    v0 << 30.0*deg_to_rad, 5.0*deg_to_rad, 10.0*deg_to_rad; //constant rate-of-turn in rad/s
-    const_diff_ox.resize(N/dt);
-    const_diff_oy.resize(N/dt);
-    const_diff_oz.resize(N/dt);
-    cdox_abs.resize(N/dt);
-    cdoy_abs.resize(N/dt);
-    cdoz_abs.resize(N/dt);
-    vector0 = VectorXs::Zero(N/dt);
-    t_vec.resize(N/dt);
-    ox.resize(N/dt);
-    oy.resize(N/dt);
-    oz.resize(N/dt);
-    qox.resize(N/dt);
-    qoy.resize(N/dt);
-    qoz.resize(N/dt);
-
-    for(wolf::Scalar n=0; n<N/dt; n++){
-        v2 = q2v(v2q(v0*n*dt));
-        ox(n) = v2(0);
-        oy(n) = v2(1);
-        oz(n) = v2(2);
-        /*ox(n) = pi2pi(v0(0)*n*dt);
-        oy(n) = pi2pi(v0(1)*n*dt);
-        oz(n) = pi2pi(v0(2)*n*dt);*/
-        t_vec(n) = n*dt;
-    }
+    Eigen::Vector3s tmp_vec; //will be used to store rate of turn data
 
-    for(wolf::Scalar n=0; n<N/dt; n++){
-        if(n!=0)
-            q0 = q0 * v2q(v0*dt); //succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)
-        v1 = q2v(q0);   //corresponding rotation vector of current quaternion
-        qox(n) = v1(0); //angle X component
-        qoy(n) = v1(1); //angle Y component
-        qoz(n) = v1(2); //angle Z component
-    }
+    const unsigned int x_rot_vel = 5;   // deg/s
+    const unsigned int y_rot_vel = 2;   // deg/s
+    const unsigned int z_rot_vel = 10;  // deg/s
+
+    wolf::Scalar tmpx, tmpy, tmpz;
+    /*
+        ox oy oz evolution in degrees (for understanding) --> converted in rad
+        with * pi/180
+        ox = x_rot_vel * t; %express angle in rad before using sinus
+        oy = y_rot_vel * t;
+        oz = z_rot_vel * t;
+
+        corresponding rate of turn
+        %rate of turn expressed in radians/s
+        wx = x_rot_vel;
+        wy = y_rot_vel;
+        wz = z_rot_vel;
+     */
+
+     //there is no need to compute the rate of turn at each time because it is constant here : 
+    tmpx = deg_to_rad * x_rot_vel;  // rad/s
+    tmpy = deg_to_rad * y_rot_vel;
+    tmpz = deg_to_rad * z_rot_vel;
+    tmp_vec << tmpx, tmpy, tmpz;
+    const wolf::Scalar dt = 0.1;
+
+    for(unsigned int data_iter = 0; data_iter < 100; data_iter ++)
+    {   
+        rot0 = rot0 * v2R(tmp_vec*dt);
+        q0 = q0 * v2q(tmp_vec*dt); //succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)
 
-    //Compute difference between orientation vectors (expected - real)
-    const_diff_ox = ox - qox;
-    const_diff_oy = oy - qoy;
-    const_diff_oz = oz - qoz;
-
-    //get absolute difference
-    cdox_abs = const_diff_ox.array().abs();
-    cdoy_abs = const_diff_oy.array().abs();
-    cdoz_abs = const_diff_oz.array().abs();
-
-    ASSERT_TRUE((ox - qox).isMuchSmallerThan(1,0.000001) && (oy - qoy).isMuchSmallerThan(1,0.000001) && (oz - qoz).isMuchSmallerThan(1,0.000001)) <<
-            "max orientation error in abs value (x, y, z) : " << cdox_abs.maxCoeff() << "\t" << cdoy_abs.maxCoeff() << "\t" << cdoz_abs.maxCoeff() << std::endl;
-
-#ifdef write_results
-    std::ofstream const_rot;
-    const_rot.open("const_rot.dat");
-    if(const_rot){
-        const_rot << "%%timestamp\t" << "ox\t" << "oy\t" << "oz\t" << "qox\t" << "qoy\t" << "qoz\t" << "\n";
-        for(int i = 0; i<N/dt; i++)
-            const_rot << t_vec(i) << "\t" << ox(i) << "\t" << oy(i) << "\t" << oz(i) << "\t" << qox(i) << "\t" << qoy(i) << "\t" << qoz(i) << "\n";
-        const_rot.close();
     }
-    else
-        PRINTF("could not open file const_rot");
-#endif
 
+    // Compare results from rotation matrix composition and quaternion composition
+     qRot = (v2q(R2v(rot0)));
+     
+     Eigen::Vector3s final_orientation(q2v(qRot));
+     ASSERT_TRUE((final_orientation - wolf::q2v(q0)).isMuchSmallerThan(1,wolf::Constants::EPS)) << "final orientation expected : " << final_orientation.transpose() << 
+     "\n computed final orientation : " << wolf::q2v(q0).transpose() << std::endl;
 }
 
 TEST(rotations, Quat_compos_var_rateOfTurn)
 {
     using namespace wolf;
 
-    //********* changing rate of turn - same freq for all axis *********
+                                //********* changing rate of turn - same freq for all axis *********
+
+    /* First idea was to integrate data on SO3 (succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)) and in R3
+    (q2v(v2q(v0*n*dt))). with v0 << 30.0*deg_to_rad, 5.0*deg_to_rad, 10.0*deg_to_rad : constant rate-of-turn in rad/s and dt the time step.
+    But this is not OK, we cannot expect those 2 rotation integration to be equal.
+    The whole point of the SO3 thing is that we cannot integrate rotation in the R3 space and expect it to work. This is why we must integrate it in the manifold of SO3
+    
+    more specifically : 
+    - At a constant velocity, because we keep a constant rotation axis, the integral is the same.
+    - for non-contant velocities, especially if we change the axis of rotation, then it’s not the same, and the only good method is the SO3.
+
+    We change the idea :
+    define orientation and derive ox, oy, oz so that we get the rate of turn wx, wy, wz.
+    Then compare the final orientation from ox, oy, oz and quaternion we get by data integration
+
+     ******* RESULT : ******* 
+    The error in this test is due to discretization. The smaller is dt and the better is the integration !
+    with dt = 0.001, the error is in 1e-5
+    */
+
     wolf::Scalar deg_to_rad = M_PI/180.0;
-    Quaternions q0;
+    Eigen::Matrix3s rot0(Eigen::Matrix3s::Identity());
+    Eigen::Quaternions q0, qRot;
     q0.setIdentity();
-    Vector3s v0, v1, v2;
-    VectorXs const_diff_ox, const_diff_oy, const_diff_oz, ox, oy, oz, qox, qoy, qoz;
-    VectorXs cdox_abs, cdoy_abs, cdoz_abs, vector0, t_vec; //= const_diff_## with absolute values
+
+    Eigen::Vector3s tmp_vec; //will be used to store rate of turn data
+    wolf::Scalar time = 0;    
+    const unsigned int x_rot_vel = 15;   // deg/s
+    const unsigned int y_rot_vel = 15;   // deg/s
+    const unsigned int z_rot_vel = 15;  // deg/s
+
+    wolf::Scalar tmpx, tmpy, tmpz;
+    /*
+        ox oy oz evolution in degrees (for understanding) --> converted in rad
+        with * pi/180
+        ox = pi*sin(x_rot_vel * t * pi/180); %express angle in rad before using sinus
+        oy = pi*sin(y_rot_vel * t * pi/180);
+        oz = pi*sin(z_rot_vel * t * pi/180);
+
+        corresponding rate of turn
+        %rate of turn expressed in radians/s
+        wx = pi * x_rot_vel * cos(x_rot_vel * t * pi/180) * pi/180;
+        wy = pi * y_rot_vel * cos(y_rot_vel * t * pi/180) * pi/180;
+        wz = pi * z_rot_vel * cos(z_rot_vel * t * pi/180) * pi/180;
+     */
+
     const wolf::Scalar dt = 0.001;
-    const wolf::Scalar N = 100;
-
-    const_diff_ox.resize(N/dt);
-    const_diff_oy.resize(N/dt);
-    const_diff_oz.resize(N/dt);
-    cdox_abs.resize(N/dt);
-    cdoy_abs.resize(N/dt);
-    cdoz_abs.resize(N/dt);
-    vector0 = VectorXs::Zero(N/dt);
-    t_vec.resize(N/dt);
-    ox.resize(N/dt);
-    oy.resize(N/dt);
-    oz.resize(N/dt);
-    qox.resize(N/dt);
-    qoy.resize(N/dt);
-    qoz.resize(N/dt);
-
-    wolf::Scalar alpha, beta, gamma;
-    alpha = 10;
-    beta = 10;
-    gamma = 10;
-    v0 << alpha*deg_to_rad, beta*deg_to_rad, gamma*deg_to_rad;
-
-    for(wolf::Scalar n=0; n<N/dt; n++){
-        v1 << sin(v0(0)*n*dt), sin(v0(1)*n*dt), sin(v0(2)*n*dt);
-        v1 = q2v(v2q(v1));
-        ox(n) = v1(0);
-        oy(n) = v1(1);
-        oz(n) = v1(2);
-        /*ox(n) = pi2pi(v0(0)*n*dt);
-        oy(n) = pi2pi(v0(1)*n*dt);
-        oz(n) = pi2pi(v0(2)*n*dt);*/
-        t_vec(n) = n*dt;
-    }
 
-    for(wolf::Scalar n=0; n<N/dt; n++){
-        if(n!=0){
-            v2 << v0(0)*cos(v0(0)*n*dt), v0(1)*cos(v0(1)*n*dt), v0(2)*cos(v0(2)*n*dt);
-            q0 = q0 * v2q(v2*dt); //succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)
-        }
-        v1 = q2v(q0);   //corresponding rotation vector of current quaternion
-        qox(n) = v1(0); //angle X component
-        qoy(n) = v1(1); //angle Y component
-        qoz(n) = v1(2); //angle Z component
-    }
+    for(unsigned int data_iter = 0; data_iter <= 10000; data_iter ++)
+    {   
+        tmpx = M_PI*x_rot_vel*cos(wolf::toRad(x_rot_vel * time))*deg_to_rad;
+        tmpy = M_PI*y_rot_vel*cos(wolf::toRad(y_rot_vel * time))*deg_to_rad;
+        tmpz = M_PI*z_rot_vel*cos(wolf::toRad(z_rot_vel * time))*deg_to_rad;
+        tmp_vec << tmpx, tmpy, tmpz;
 
-    //Compute difference between orientation vectors (expected - real)
-    const_diff_ox = ox - qox;
-    const_diff_oy = oy - qoy;
-    const_diff_oz = oz - qoz;
-
-    //get absolute difference
-    cdox_abs = const_diff_ox.array().abs();
-    cdoy_abs = const_diff_oy.array().abs();
-    cdoz_abs = const_diff_oz.array().abs();
-
-    ASSERT_FALSE(cdox_abs.isMuchSmallerThan(1,wolf::Constants::EPS) && cdoy_abs.isMuchSmallerThan(1,wolf::Constants::EPS) && cdoz_abs.isMuchSmallerThan(1,wolf::Constants::EPS)) <<
-            "max orientation error in abs value (x, y, z) : " << cdox_abs.maxCoeff() << "\t" << cdoy_abs.maxCoeff() << "\t" << cdoz_abs.maxCoeff() << std::endl;
-
-#ifdef write_results
-    std::ofstream sin_rot0;
-    sin_rot0.open("sin_rot0.dat");
-    if(sin_rot0){
-        sin_rot0 << "%%timestamp\t" << "ox\t" << "oy\t" << "oz\t" << "qox\t" << "qoy\t" << "qoz\t" << "\n";
-        for(int i = 0; i<N/dt; i++)
-            sin_rot0 << t_vec(i) << "\t" << ox(i) << "\t" << oy(i) << "\t" << oz(i) << "\t" << qox(i) << "\t" << qoy(i) << "\t" << qoz(i) << "\n";
-        sin_rot0.close();
+        rot0 = rot0 * v2R(tmp_vec*dt);
+        q0 = q0 * v2q(tmp_vec*dt); //succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)
+
+        time += dt;
     }
-    else
-        PRINTF("could not open file sin_rot0");
-#endif
+
+    // Compare results from rotation matrix composition and quaternion composition
+    qRot = (v2q(R2v(rot0)));
+     
+    Eigen::Vector3s final_orientation(q2v(qRot));
+     
+    EXPECT_TRUE((final_orientation - wolf::q2v(q0)).isMuchSmallerThan(1,wolf::Constants::EPS)) << "final orientation expected : " << final_orientation.transpose() << 
+    "\n computed final orientation : " << wolf::q2v(q0).transpose() << std::endl;
+    ASSERT_TRUE((final_orientation - wolf::q2v(q0)).isMuchSmallerThan(1,0.0001)) << "final orientation expected : " << final_orientation.transpose() << 
+    "\n computed final orientation : " << wolf::q2v(q0).transpose() << std::endl;
+
 }
 
 TEST(rotations, Quat_compos_var_rateOfTurn_diff)
@@ -420,85 +536,76 @@ TEST(rotations, Quat_compos_var_rateOfTurn_diff)
     using namespace wolf;
 
     //      ********* changing rate of turn - different freq for 1 axis *********
+
+    /* First idea was to integrate data on SO3 (succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)) and in R3
+    (q2v(v2q(v0*n*dt))). with v0 << 30.0*deg_to_rad, 5.0*deg_to_rad, 10.0*deg_to_rad : constant rate-of-turn in rad/s and dt the time step.
+    But this is not OK, we cannot expect those 2 rotation integration to be equal.
+    The whole point of the SO3 thing is that we cannot integrate rotation in the R3 space and expect it to work. This is why we must integrate it in the manifold of SO3
+    
+    more specifically : 
+    - At a constant velocity, because we keep a constant rotation axis, the integral is the same.
+    - for non-contant velocities, especially if we change the axis of rotation, then it’s not the same, and the only good method is the SO3.
+
+    We change the idea :
+    define orientation and derive ox, oy, oz so that we get the rate of turn wx, wy, wz.
+    Then compare the final orientation from ox, oy, oz and quaternion we get by data integration
+
+    ******* RESULT : ******* 
+    Things are more tricky here. The errors go growing with time.
+    with dt = 0.001, the error is in 1e-4 for 1 s integration ! But this may also depend on the frequency given to the rotation on each of the axis.
+    */
+
     wolf::Scalar deg_to_rad = M_PI/180.0;
-    Quaternions q0;
+    Eigen::Matrix3s rot0(Eigen::Matrix3s::Identity());
+    Eigen::Quaternions q0, qRot;
     q0.setIdentity();
-    Vector3s v0, v1, v2;
-    VectorXs const_diff_ox, const_diff_oy, const_diff_oz, ox, oy, oz, qox, qoy, qoz;
-    VectorXs cdox_abs, cdoy_abs, cdoz_abs, vector0, t_vec; //= const_diff_## with absolute values
+
+    Eigen::Vector3s tmp_vec; //will be used to store rate of turn data
+    wolf::Scalar time = 0;    
+    const unsigned int x_rot_vel = 1;   // deg/s
+    const unsigned int y_rot_vel = 3;   // deg/s
+    const unsigned int z_rot_vel = 6;  // deg/s
+
+    wolf::Scalar tmpx, tmpy, tmpz;
+    /*
+        ox oy oz evolution in degrees (for understanding) --> converted in rad
+        with * pi/180
+        ox = pi*sin(x_rot_vel * t * pi/180); %express angle in rad before using sinus
+        oy = pi*sin(y_rot_vel * t * pi/180);
+        oz = pi*sin(z_rot_vel * t * pi/180);
+
+        corresponding rate of turn
+        %rate of turn expressed in radians/s
+        wx = pi * x_rot_vel * cos(x_rot_vel * t * pi/180) * pi/180;
+        wy = pi * y_rot_vel * cos(y_rot_vel * t * pi/180) * pi/180;
+        wz = pi * z_rot_vel * cos(z_rot_vel * t * pi/180) * pi/180;
+     */
+
     const wolf::Scalar dt = 0.001;
-    const wolf::Scalar N = 100;
-
-    const_diff_ox.resize(N/dt);
-    const_diff_oy.resize(N/dt);
-    const_diff_oz.resize(N/dt);
-    cdox_abs.resize(N/dt);
-    cdoy_abs.resize(N/dt);
-    cdoz_abs.resize(N/dt);
-    vector0 = VectorXs::Zero(N/dt);
-    t_vec.resize(N/dt);
-    ox.resize(N/dt);
-    oy.resize(N/dt);
-    oz.resize(N/dt);
-    qox.resize(N/dt);
-    qoy.resize(N/dt);
-    qoz.resize(N/dt);
-
-    wolf::Scalar alpha, beta, gamma;
-    alpha = 10;
-    beta = 5;
-    gamma = 10;
-    v0 << alpha*deg_to_rad, beta*deg_to_rad, gamma*deg_to_rad;
-
-    for(wolf::Scalar n=0; n<N/dt; n++){
-        v1 << sin(v0(0)*n*dt), sin(v0(1)*n*dt), sin(v0(2)*n*dt);
-        v1 = q2v(v2q(v1));
-        ox(n) = v1(0);
-        oy(n) = v1(1);
-        oz(n) = v1(2);
-        /*ox(n) = pi2pi(v0(0)*n*dt);
-        oy(n) = pi2pi(v0(1)*n*dt);
-        oz(n) = pi2pi(v0(2)*n*dt);*/
-        t_vec(n) = n*dt;
-    }
 
-    for(wolf::Scalar n=0; n<N/dt; n++){
-        if(n!=0){
-            v2 << v0(0)*cos(v0(0)*n*dt), v0(1)*cos(v0(1)*n*dt), v0(2)*cos(v0(2)*n*dt);
-            q0 = q0 * v2q(v2*dt); //succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)
-        }
-        v1 = q2v(q0);   //corresponding rotation vector of current quaternion
-        qox(n) = v1(0); //angle X component
-        qoy(n) = v1(1); //angle Y component
-        qoz(n) = v1(2); //angle Z component
-    }
+    for(unsigned int data_iter = 0; data_iter <= 1000; data_iter ++)
+    {   
+        tmpx = M_PI*x_rot_vel*cos(wolf::toRad(x_rot_vel * time))*deg_to_rad;
+        tmpy = M_PI*y_rot_vel*cos(wolf::toRad(y_rot_vel * time))*deg_to_rad;
+        tmpz = M_PI*z_rot_vel*cos(wolf::toRad(z_rot_vel * time))*deg_to_rad;
+        tmp_vec << tmpx, tmpy, tmpz;
 
-    //Compute difference between orientation vectors (expected - real)
-    const_diff_ox = ox - qox;
-    const_diff_oy = oy - qoy;
-    const_diff_oz = oz - qoz;
-
-    //get absolute difference
-    cdox_abs = const_diff_ox.array().abs();
-    cdoy_abs = const_diff_oy.array().abs();
-    cdoz_abs = const_diff_oz.array().abs();
-
-    ASSERT_FALSE(cdox_abs.isMuchSmallerThan(1,wolf::Constants::EPS) && cdoy_abs.isMuchSmallerThan(1,wolf::Constants::EPS) && cdoz_abs.isMuchSmallerThan(1,wolf::Constants::EPS)) <<
-            "max orientation error in abs value (x, y, z) : " << cdox_abs.maxCoeff() << "\t" << cdoy_abs.maxCoeff() << "\t" << cdoz_abs.maxCoeff() << std::endl;
-    //std::cout << "\t quaternion composition with constant rate of turn is NOT OK\n" << std::endl;
-    //std::cout << "max orientation error in abs value (x, y, z) : " << cdox_abs.maxCoeff() << "\t" << cdoy_abs.maxCoeff() << "\t" << cdoz_abs.maxCoeff() << std::endl;
-#ifdef write_results
-    std::ofstream sin_rot;
-    sin_rot.open("sin_rot.dat");
-    if(sin_rot){
-        sin_rot << "%%timestamp\t" << "ox\t" << "oy\t" << "oz\t" << "qox\t" << "qoy\t" << "qoz\t" << "\n";
-        for(int i = 0; i<N/dt; i++)
-            sin_rot << t_vec(i) << "\t" << ox(i) << "\t" << oy(i) << "\t" << oz(i) << "\t" << qox(i) << "\t" << qoy(i) << "\t" << qoz(i) << "\n";
-        sin_rot.close();
+        rot0 = rot0 * v2R(tmp_vec*dt);
+        q0 = q0 * v2q(tmp_vec*dt); //succesive composition of quaternions : q = q * dq(w*dt) <=> q = q * dq(w*dt) * q' (mathematically)
+
+        time += dt;
     }
-    else
-        PRINTF("could not open file sin_rot");
-#endif
+
+    // Compare results from rotation matrix composition and quaternion composition
+    qRot = (v2q(R2v(rot0)));
+     
+    Eigen::Vector3s final_orientation(q2v(qRot));
+
+    EXPECT_TRUE((final_orientation - wolf::q2v(q0)).isMuchSmallerThan(1,wolf::Constants::EPS)) << "final orientation expected : " << final_orientation.transpose() << 
+    "\n computed final orientation : " << wolf::q2v(q0).transpose() << std::endl;
+     
+    ASSERT_TRUE((final_orientation - wolf::q2v(q0)).isMuchSmallerThan(1,0.001)) << "final orientation expected : " << final_orientation.transpose() << 
+    "\n computed final orientation : " << wolf::q2v(q0).transpose() << std::endl;
 }
 
 TEST(rotations, q2R_R2q)
diff --git a/src/time_stamp.h b/src/time_stamp.h
index ad9c78a146cf1ee4bca20ea1e92c03134199784a..f0d0eede36cfd156a52d64dc9b386a322c67d784 100644
--- a/src/time_stamp.h
+++ b/src/time_stamp.h
@@ -254,6 +254,8 @@ inline TimeStamp TimeStamp::operator +(const Scalar& dt) const
     return TimeStamp(time_stamp_ + dt);
 }
 
+static const TimeStamp InvalidStamp(-1,-1);
+
 } // namespace wolf
 
 #endif
diff --git a/src/wolf.h b/src/wolf.h
index 257f71c5eb2a338d5106d761942dd20b8255d3c3..baec7de52571ee8046199f082b79cbb4600470b1 100644
--- a/src/wolf.h
+++ b/src/wolf.h
@@ -9,6 +9,7 @@
 #define WOLF_H_
 
 // Enable project-specific definitions and macros
+#include "internal/config.h"
 #include "logging.h"
 
 //includes from Eigen lib
@@ -21,7 +22,6 @@
 #include <list>
 #include <map>
 #include <memory> // shared_ptr and weak_ptr
-#include "internal/config.h"
 
 namespace wolf {
 
@@ -89,6 +89,7 @@ typedef Matrix<wolf::Scalar, 1, 1> Vector1s;                ///< 1-vector of rea
 typedef Matrix<wolf::Scalar, 2, 1> Vector2s;                ///< 2-vector of real Scalar type
 typedef Matrix<wolf::Scalar, 3, 1> Vector3s;                ///< 3-vector of real Scalar type
 typedef Matrix<wolf::Scalar, 4, 1> Vector4s;                ///< 4-vector of real Scalar type
+typedef Matrix<wolf::Scalar, 5, 1> Vector5s;                ///< 5-vector of real Scalar type
 typedef Matrix<wolf::Scalar, 6, 1> Vector6s;                ///< 6-vector of real Scalar type
 typedef Matrix<wolf::Scalar, 7, 1> Vector7s;                ///< 7-vector of real Scalar type
 typedef Matrix<wolf::Scalar, Dynamic, 1> VectorXs;          ///< variable size vector of real Scalar type
@@ -105,6 +106,11 @@ typedef Rotation2D<wolf::Scalar> Rotation2Ds;               ///< Rotation2D of r
 
 // 3. Sparse matrix
 typedef SparseMatrix<wolf::Scalar, RowMajor, int> SparseMatrixs;
+typedef Transform<wolf::Scalar,2,Affine> Affine2ds;         ///< Affine2d of real Scalar type
+typedef Transform<wolf::Scalar,3,Affine> Affine3ds;         ///< Affine3d of real Scalar type
+
+typedef Transform<wolf::Scalar,2,Isometry> Isometry2ds;     ///< Isometry2d of real Scalar type
+typedef Transform<wolf::Scalar,3,Isometry> Isometry3ds;     ///< Isometry3d of real Scalar type
 }
 
 namespace wolf {
@@ -203,6 +209,7 @@ typedef enum
     CTR_GPS_PR_3D,              ///< 3D GPS Pseudorange constraint.
     CTR_FIX,                    ///< Fix constraint (for priors).
     CTR_FIX_3D,                 ///< Fix constraint (for priors) in 3D.
+    CTR_FIX_BIAS,               ///< Fix constraint (for priors) on bias.
     CTR_ODOM_2D,                ///< 2D Odometry constraint .
     CTR_ODOM_3D,                ///< 3D Odometry constraint .
     CTR_CORNER_2D,              ///< 2D corner constraint .
@@ -326,19 +333,40 @@ WOLF_PTR_TYPEDEFS(LocalParametrizationBase);
 // Some dangling functions
 
 inline const Eigen::Vector3s gravity(void) {
-    return Eigen::Vector3s(0,0,-9.8);
+    return Eigen::Vector3s(0,0,-9.806);
 }
-//===================================================
 
+template <typename T, int N>
+bool isSymmetric(const Eigen::Matrix<T, N, N>& M,
+                 const T eps = wolf::Constants::EPS)
+{
+  return M.isApprox(M.transpose(), eps);
+}
 
-//===================================================
-// Some macros
+template <typename T, int N>
+bool isPositiveSemiDefinite(const Eigen::Matrix<T, N, N>& M)
+{
+  Eigen::SelfAdjointEigenSolver<Eigen::Matrix<T, N, N> > eigensolver(M);
+
+  if (eigensolver.info() == Eigen::Success)
+  {
+    // All eigenvalues must be >= 0:
+    return (eigensolver.eigenvalues().array() >= T(0)).all();
+  }
 
-#define WOLF_DEBUG_HERE \
-{ \
-    char this_file[] = __FILE__; \
-    std::cout << ">> " << basename(this_file) << " : " << __FUNCTION__ << "() : " << __LINE__ << std::endl; \
+  return false;
 }
+
+template <typename T, int N>
+bool isCovariance(const Eigen::Matrix<T, N, N>& M)
+{
+  return isSymmetric(M) && isPositiveSemiDefinite(M);
+}
+
+#define WOLF_ASSERT_COVARIANCE_MATRIX(x) \
+  assert(x.determinant() > 0 && "Not positive definite measurement covariance"); \
+  assert(isCovariance(x) && "Not a covariance");
+
 //===================================================
 
 } // namespace wolf
diff --git a/src/yaml/processor_image_yaml.cpp b/src/yaml/processor_image_yaml.cpp
index 9a5e344879f023b88d77cbefe532be842bc207df..e921ce10cecfc89fa8c1a1429aacda4552bb0fb3 100644
--- a/src/yaml/processor_image_yaml.cpp
+++ b/src/yaml/processor_image_yaml.cpp
@@ -84,8 +84,8 @@ static ProcessorParamsBasePtr createProcessorParamsImage(const std::string & _fi
 }
 
 // Register in the SensorFactory
-const bool registered_prc_image_feature_par = ProcessorParamsFactory::get().registerCreator("IMAGE FEATURE", createProcessorParamsImage);
-const bool registered_prc_image_landmark_par = ProcessorParamsFactory::get().registerCreator("IMAGE LANDMARK", createProcessorParamsImage);
+const bool WOLF_UNUSED registered_prc_image_feature_par = ProcessorParamsFactory::get().registerCreator("IMAGE FEATURE", createProcessorParamsImage);
+const bool WOLF_UNUSED registered_prc_image_landmark_par = ProcessorParamsFactory::get().registerCreator("IMAGE LANDMARK", createProcessorParamsImage);
 
 
 }
diff --git a/src/yaml/processor_imu_yaml.cpp b/src/yaml/processor_imu_yaml.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..8ac801dd2da793cbd5a0f3e14efcd14502931d50
--- /dev/null
+++ b/src/yaml/processor_imu_yaml.cpp
@@ -0,0 +1,59 @@
+/**
+ * \file processor_imu_yaml.cpp
+ *
+ *  Created on: jan 19, 2017
+ *      \author: Dinesh Atchuthan
+ */
+
+// wolf yaml
+#include "yaml_conversion.h"
+
+// wolf
+#include "../processor_imu.h"
+#include "../factory.h"
+
+// yaml-cpp library
+#include <yaml-cpp/yaml.h>
+
+namespace wolf
+{
+
+namespace
+{
+static ProcessorParamsBasePtr createProcessorIMUParams(const std::string & _filename_dot_yaml)
+{
+    YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
+
+    if (config["processor type"].as<std::string>() == "IMU")
+    {
+
+        // YAML:: to Eigen::
+        using namespace Eigen;
+        std::string processor_type = config["processor type"]     .as<std::string>();
+        std::string processor_name = config["processor name"]     .as<std::string>();
+
+        YAML::Node kf_vote = config["keyframe vote"];
+
+        ProcessorIMUParamsPtr params = std::make_shared<ProcessorIMUParams>();
+
+        params->type                = processor_type;
+        params->name                = processor_name;
+        params->max_time_span       = kf_vote["max time span"]      .as<Scalar>();
+        params->max_buff_length     = kf_vote["max buffer length"]  .as<Size  >();
+        params->dist_traveled       = kf_vote["dist traveled"]      .as<Scalar>();
+        params->angle_turned        = kf_vote["angle turned"]       .as<Scalar>();
+        params->voting_active       = kf_vote["voting_active"]      .as<bool>();
+
+        return params;
+    }
+
+    std::cout << "Bad configuration file. No processor type found." << std::endl;
+    return nullptr;
+}
+
+// Register in the SensorFactory
+const bool WOLF_UNUSED registered_prc_odom_3D = ProcessorParamsFactory::get().registerCreator("IMU", createProcessorIMUParams);
+
+} // namespace [unnamed]
+
+} // namespace wolf
diff --git a/src/yaml/processor_odom_3D_yaml.cpp b/src/yaml/processor_odom_3D_yaml.cpp
index 9a20f5c7ce7ed3d5193757eb3d59cd54fe2f4118..a8fbce5997d01b90abc2340fddb2556f4bfc2f91 100644
--- a/src/yaml/processor_odom_3D_yaml.cpp
+++ b/src/yaml/processor_odom_3D_yaml.cpp
@@ -51,7 +51,7 @@ static ProcessorParamsBasePtr createProcessorOdom3DParams(const std::string & _f
 }
 
 // Register in the SensorFactory
-const bool registered_prc_odom_3D = ProcessorParamsFactory::get().registerCreator("ODOM 3D", createProcessorOdom3DParams);
+const bool WOLF_UNUSED registered_prc_odom_3D = ProcessorParamsFactory::get().registerCreator("ODOM 3D", createProcessorOdom3DParams);
 
 } // namespace [unnamed]
 
diff --git a/src/yaml/sensor_camera_yaml.cpp b/src/yaml/sensor_camera_yaml.cpp
index a2feb6fe4a68d55fb9c2074e46c21566f9700f0d..c3c94d6b4fbcd00fb40d9781f18501b4290f81a6 100644
--- a/src/yaml/sensor_camera_yaml.cpp
+++ b/src/yaml/sensor_camera_yaml.cpp
@@ -91,7 +91,7 @@ static IntrinsicsBasePtr createIntrinsicsCamera(const std::string & _filename_do
 }
 
 // Register in the SensorFactory
-const bool registered_camera_intr = IntrinsicsFactory::get().registerCreator("CAMERA", createIntrinsicsCamera);
+const bool WOLF_UNUSED registered_camera_intr = IntrinsicsFactory::get().registerCreator("CAMERA", createIntrinsicsCamera);
 
 } // namespace [unnamed]
 
diff --git a/src/yaml/sensor_imu_yaml.cpp b/src/yaml/sensor_imu_yaml.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..babce6140ffdb9046448fa0120b94f0cc72b364d
--- /dev/null
+++ b/src/yaml/sensor_imu_yaml.cpp
@@ -0,0 +1,60 @@
+/**
+ * \file sensor_imu_yaml.cpp
+ *
+ *  Created on: Jan 18, 2017
+ *      \author: Dinesh Atchuthan
+ */
+
+// wolf yaml
+#include "yaml_conversion.h"
+
+// wolf
+#include "../sensor_imu.h"
+#include "../factory.h"
+
+// yaml-cpp library
+#include <yaml-cpp/yaml.h>
+
+namespace wolf
+{
+
+namespace
+{
+
+static IntrinsicsBasePtr createIntrinsicsIMU(const std::string & _filename_dot_yaml)
+{
+    YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
+
+    if (config["sensor type"].as<std::string>() == "IMU")
+    {
+
+        // YAML:: to Eigen::
+        using namespace Eigen;
+        std::string sensor_type = config["sensor type"]     .as<std::string>();
+        std::string sensor_name = config["sensor name"]     .as<std::string>();
+
+        YAML::Node variances    = config["motion variances"];
+        YAML::Node kf_vote      = config["keyframe vote"];
+
+        IntrinsicsIMUPtr params = std::make_shared<IntrinsicsIMU>();
+
+        params->a_noise     = variances["a_noise"]  .as<Scalar>();
+        params->w_noise      = variances["w_noise"]   .as<Scalar>();
+        params->ab_initial_stdev     = variances["ab_initial_stdev"]     .as<Scalar>();
+        params->wb_initial_stdev     = variances["wb_initial_stdev"]     .as<Scalar>();
+        params->ab_rate_stdev        = variances["ab_rate_stdev"]     .as<Scalar>();
+        params->wb_rate_stdev        = variances["wb_rate_stdev"]     .as<Scalar>();
+
+        return params;
+    }
+
+    std::cout << "Bad configuration file. No sensor type found." << std::endl;
+    return nullptr;
+}
+
+// Register in the SensorFactory
+const bool WOLF_UNUSED registered_imu_intr = IntrinsicsFactory::get().registerCreator("IMU", createIntrinsicsIMU);
+
+} // namespace [unnamed]
+
+} // namespace wolf
diff --git a/src/yaml/sensor_laser_2D_yaml.cpp b/src/yaml/sensor_laser_2D_yaml.cpp
index c703d73059545c14f3303c34375a79c7b2df89ed..160386e6ea9f3b005ab1ea073ffe6bcf269c3d4c 100644
--- a/src/yaml/sensor_laser_2D_yaml.cpp
+++ b/src/yaml/sensor_laser_2D_yaml.cpp
@@ -31,7 +31,7 @@ IntrinsicsBasePtr createIntrinsicsLaser2D(const std::string& _filename_dot_yaml)
 
 
 // register into factory
-const bool registered_laser_params = IntrinsicsFactory::get().registerCreator("LASER 2D", createIntrinsicsLaser2D);
+const bool WOLF_UNUSED registered_laser_params = IntrinsicsFactory::get().registerCreator("LASER 2D", createIntrinsicsLaser2D);
 
 } // namespace [void]
 } // namespace wolf
diff --git a/src/yaml/sensor_odom_3D_yaml.cpp b/src/yaml/sensor_odom_3D_yaml.cpp
index 5501666e7e5fce8fa098cd5f8a14324c8594365a..a6012aeef037ba22493f562969614ff885341aa4 100644
--- a/src/yaml/sensor_odom_3D_yaml.cpp
+++ b/src/yaml/sensor_odom_3D_yaml.cpp
@@ -51,7 +51,7 @@ static IntrinsicsBasePtr createIntrinsicsOdom3D(const std::string & _filename_do
 }
 
 // Register in the SensorFactory
-const bool registered_odom_3D_intr = IntrinsicsFactory::get().registerCreator("ODOM 3D", createIntrinsicsOdom3D);
+const bool WOLF_UNUSED registered_odom_3D_intr = IntrinsicsFactory::get().registerCreator("ODOM 3D", createIntrinsicsOdom3D);
 
 } // namespace [unnamed]